From 7b55dbbfc2cff5a1d0ecec2d852f907b9027ff30 Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Fri, 11 Oct 2019 09:17:00 +0200 Subject: [PATCH 1/9] Added files for PR --- .../FrenetOptimalTrajectory/path_planner.py | 547 + .../FrenetOptimalTrajectory/racing_line.py | 80 + .../FrenetOptimalTrajectory/track.json | 19864 ++++++++++++++++ 3 files changed, 20491 insertions(+) create mode 100644 PathPlanning/FrenetOptimalTrajectory/path_planner.py create mode 100644 PathPlanning/FrenetOptimalTrajectory/racing_line.py create mode 100644 PathPlanning/FrenetOptimalTrajectory/track.json diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py new file mode 100644 index 0000000000..53a9fe5ec9 --- /dev/null +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -0,0 +1,547 @@ +""" + +Frenet optimal trajectory generator + +author: Atsushi Sakai (@Atsushi_twi) + +Ref: + +- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame](https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) + +- [Optimal trajectory generation for dynamic street scenarios in a Frenet Frame](https://www.youtube.com/watch?v=Cj6tAQe7UCY) + +""" + +import numpy as np +import matplotlib.pyplot as plt +import copy +import math +import cubic_spline_planner +import racing_line +import sys +import time + +SIM_LOOP = 5000 + +# Parameter +MAX_SPEED = 60.0 / 3.6 # maximum speed [m/s] +MAX_ACCEL = 10.0 # maximum acceleration [m/ss] +MAX_CURVATURE = 100.0 # maximum curvature [1/m] +MAX_ROAD_WIDTH = 7.0 # maximum road width [m] +D_ROAD_W = 1.0 # road width sampling length [m] +DT = 0.2 # time tick [s] +MAXT = 4.0 # max prediction time [m] +MINT = 2.0 # min prediction time [m] +TARGET_SPEED = 60.0 / 3.6 # target speed [m/s] +D_T_S = 10.0 / 3.6 # target speed sampling length [m/s] +N_S_SAMPLE = 0.2 # sampling number of target speed +ROBOT_RADIUS = 1.0 # robot radius [m] + +# cost weights +KJ = 0.1 +KT = 0.1 +KD = 5.0 +KLAT = 5.0 +KLON = 1.0 + +show_animation = True + +class quintic_polynomial: + + def __init__(self, xs, vxs, axs, xe, vxe, axe, T): + + # calc coefficient of quintic polynomial + self.xs = xs + self.vxs = vxs + self.axs = axs + self.xe = xe + self.vxe = vxe + self.axe = axe + + self.a0 = xs + self.a1 = vxs + self.a2 = axs / 2.0 + + A = np.array([[T**3, T**4, T**5], + [3 * T ** 2, 4 * T ** 3, 5 * T ** 4], + [6 * T, 12 * T ** 2, 20 * T ** 3]]) + b = np.array([xe - self.a0 - self.a1 * T - self.a2 * T**2, + vxe - self.a1 - 2 * self.a2 * T, + axe - 2 * self.a2]) + x = np.linalg.solve(A, b) + + self.a3 = x[0] + self.a4 = x[1] + self.a5 = x[2] + + def calc_point(self, t): + xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ + self.a3 * t**3 + self.a4 * t**4 + self.a5 * t**5 + + return xt + + def calc_first_derivative(self, t): + xt = self.a1 + 2 * self.a2 * t + \ + 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 5 * self.a5 * t**4 + + return xt + + def calc_second_derivative(self, t): + xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + 20 * self.a5 * t**3 + + return xt + + def calc_third_derivative(self, t): + xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t**2 + + return xt + + +class quartic_polynomial: + + def __init__(self, xs, vxs, axs, vxe, axe, T): + + # calc coefficient of quintic polynomial + self.xs = xs + self.vxs = vxs + self.axs = axs + self.vxe = vxe + self.axe = axe + + self.a0 = xs + self.a1 = vxs + self.a2 = axs / 2.0 + + A = np.array([[3 * T ** 2, 4 * T ** 3], + [6 * T, 12 * T ** 2]]) + b = np.array([vxe - self.a1 - 2 * self.a2 * T, + axe - 2 * self.a2]) + x = np.linalg.solve(A, b) + + self.a3 = x[0] + self.a4 = x[1] + + def calc_point(self, t): + xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ + self.a3 * t**3 + self.a4 * t**4 + + return xt + + def calc_first_derivative(self, t): + xt = self.a1 + 2 * self.a2 * t + \ + 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + + return xt + + def calc_second_derivative(self, t): + xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + + return xt + + def calc_third_derivative(self, t): + xt = 6 * self.a3 + 24 * self.a4 * t + + return xt + + +class Frenet_path: + + def __init__(self): + self.t = [] + self.d = [] + self.d_d = [] + self.d_dd = [] + self.d_ddd = [] + self.s = [] + self.s_d = [] + self.s_dd = [] + self.s_ddd = [] + self.cd = 0.0 + self.cv = 0.0 + self.cf = 0.0 + + self.x = [] + self.y = [] + self.yaw = [] + self.ds = [] + self.c = [] + + +def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): + + frenet_paths = [] + + # generate path to each offset goal + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + + # Lateral motion planning + for Ti in np.arange(MINT, MAXT, DT): + fp = Frenet_path() + + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.d = [lat_qp.calc_point(t) for t in fp.t] + fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] + fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] + fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + + # Longitudinal motion planning (Velocity keeping) + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + tfp = copy.deepcopy(fp) + lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + + tfp.s = [lon_qp.calc_point(t) for t in fp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + + Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk + Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk + + # square of diff from target speed + ds = (TARGET_SPEED - tfp.s_d[-1])**2 + + tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 + tfp.cv = KJ * Js + KT * Ti + KD * ds + tfp.cf = KLAT * tfp.cd + KLON * tfp.cv + + frenet_paths.append(tfp) + + return frenet_paths + + +def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0): + + frenet_paths = [] + dist_safe = 20.0 + tau = 3.0 + + # generate path to each offset goal + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + + # Lateral motion planning + for Ti in np.arange(MINT, MAXT, DT): + fp = Frenet_path() + + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.d = [lat_qp.calc_point(t) for t in fp.t] + fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] + fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] + fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + + + # Longitudinal motion planning (Follow Mode) + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + tfp = copy.deepcopy(fp) + + # calculate leading vehicle pos, vel, acc + s_lv1 = s0 + c_speed * Ti + s_lv1dot = c_speed + s_lv1ddot = 0 + + # calculate target pos, vel, acc + s_target = s_lv1 - (dist_safe + tau * s_lv1dot) + s_targetdot = s_lv1dot + s_targetddot = 0 + lon_qp = quintic_polynomial(s0, c_speed, 0.0, s_target, s_targetdot - 10.0, -10.0, Ti) + + tfp.s = [lon_qp.calc_point(t) for t in fp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + + Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk + Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk + + # square of diff from target speed + ds = (TARGET_SPEED - tfp.s_d[-1])**2 + + tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 + tfp.cv = KJ * Js + KT * Ti + KD * ds + tfp.cf = KLAT * tfp.cd + KLON * tfp.cv + + frenet_paths.append(tfp) + + return frenet_paths + + + +def calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0): + frenet_paths = [] + + # Longitudinal motion planning (Velocity keeping) + for Ti in np.arange(MINT, MAXT, DT): + tfp = Frenet_path() + + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + + tfp.t = [t for t in np.arange(0.0, Ti, DT)] + tfp.s = [lon_qp.calc_point(t) for t in tfp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in tfp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in tfp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in tfp.t] + + # Lateral motion planning + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + + fp = copy.deepcopy(tfp) + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + + fp.d = [lat_qp.calc_point(s) for s in tfp.s] + fp.d_d = [lat_qp.calc_first_derivative(s) for s in tfp.s] + fp.d_dd = [lat_qp.calc_second_derivative(s) for s in tfp.s] + fp.d_ddd = [lat_qp.calc_third_derivative(s) for s in tfp.s] + + Jp = sum(np.power(fp.d_ddd, 2)) # square of jerk + Js = sum(np.power(fp.s_ddd, 2)) # square of jerk + + # square of diff from target speed + ds = (TARGET_SPEED - tfp.s_d[-1])**2 + + fp.cd = KJ * Jp + KT * Ti + KD * fp.d[-1]**2 + fp.cv = KJ * Js + KT * Ti + KD * ds + fp.cf = KLAT * fp.cd + KLON * fp.cv + + frenet_paths.append(fp) + + return frenet_paths + + +def calc_global_paths(fplist, csp): + + for fp in fplist: + + # calc global positions + for i in range(len(fp.s)): + ix, iy = csp.calc_position(fp.s[i]) + if ix is None: + break + iyaw = csp.calc_yaw(fp.s[i]) + di = fp.d[i] + fx = ix + di * math.cos(iyaw + math.pi / 2.0) + fy = iy + di * math.sin(iyaw + math.pi / 2.0) + fp.x.append(fx) + fp.y.append(fy) + + # calc yaw and ds + for i in range(len(fp.x) - 1): + dx = fp.x[i + 1] - fp.x[i] + dy = fp.y[i + 1] - fp.y[i] + fp.yaw.append(math.atan2(dy, dx)) + fp.ds.append(math.sqrt(dx**2 + dy**2)) + + fp.yaw.append(fp.yaw[-1]) + fp.ds.append(fp.ds[-1]) + + # calc curvature + for i in range(len(fp.yaw) - 1): + fp.c.append((fp.yaw[i + 1] - fp.yaw[i]) / fp.ds[i]) + + return fplist + + +def check_collision(fp, ob): + + d = [((ix - ob[0])**2 + (iy - ob[1])**2) + for (ix, iy) in zip(fp.x, fp.y)] + + collision = np.any([di <= ROBOT_RADIUS**2 for di in d]) + + if collision: + return False + + return True + + +def check_paths(fplist, ob): + + okind = [] + for i, _ in enumerate(fplist): + if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check + continue + elif any([abs(a) > MAX_ACCEL for a in fplist[i].s_dd]): # Max accel check + continue + elif any([abs(c) > MAX_CURVATURE for c in fplist[i].c]): # Max curvature check + continue + elif not check_collision(fplist[i], ob): + continue + + okind.append(i) + + return [fplist[i] for i in okind] + + +def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): + + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + + + if(len(fplist) == 0): + for i, _ in enumerate(fplist): + if(fplist[i].s_d == 0): + fplist = calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + else: + print("Follow Mode") + fplist = calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + + + # find minimum cost path + mincost = float("inf") + bestpath = None + for fp in fplist: + if mincost >= fp.cf: + mincost = fp.cf + bestpath = fp + + return bestpath + +def frenet_optimal_planning_target(csp, s0, c_speed, c_d, c_d_d, c_d_dd): + + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = calc_global_paths(fplist, csp) + + # find minimum cost path + mincost = float("inf") + bestpath = None + for fp in fplist: + if mincost >= fp.cf: + mincost = fp.cf + bestpath = fp + + return bestpath + + +def generate_target_course(x, y): + csp = cubic_spline_planner.Spline2D(x, y) + s = np.arange(0, csp.s[-1], 0.1) + + rx, ry, ryaw, rk = [], [], [], [] + for i_s in s: + ix, iy = csp.calc_position(i_s) + rx.append(ix) + ry.append(iy) + ryaw.append(csp.calc_yaw(i_s)) + rk.append(csp.calc_curvature(i_s)) + + return rx, ry, ryaw, rk, csp + + +def main(json_file): + print(__file__ + " start!!") + + rc = racing_line.RacingLine() + + rx,ry,insx,insy,outx,outy = rc.json_parser(json_file) + + + num_laps = 3 + wx, wy, targetx, targety = [], [], [], [] + + for i in range(num_laps): + wx.extend(rx) + wy.extend(ry) + targetx.extend(rx) + targety.extend(ry) + + borders_x = insx + borders_y = insy + borders_x.extend(outx) + borders_y.extend(outy) + + ob_targetx = borders_x + ob_targety = borders_y + + tx, ty, tyaw, tc, csp = generate_target_course(wx, wy) + tx_target, ty_target, tyaw_target, tc_target, csp_target = generate_target_course(targetx, targety) + + # initial state + c_speed = 0.0 / 3.6 # current speed [m/s] + c_d = 0.0 # current lateral position [m] + c_d_d = 0.0 # current lateral speed [m/s] + c_d_dd = 0.0 # current lateral acceleration [m/s] + s0 = 0. # current course position + + c_speed_target = 0.0 / 3.6 # current speed [m/s] + c_d_target = 0.0 # current lateral position [m] + c_d_d_target = 0.0 # current lateral speed [m/s] + c_d_dd_target = 0.0 # current lateral acceleration [m/s] + s0_target = 50.0 # current course position + + area = 30.0 # animation area length [m] + + for i in range(SIM_LOOP): + + # start = time.time() + + path_target = frenet_optimal_planning_target(csp_target, s0_target, + c_speed_target, c_d_target, c_d_d_target, c_d_dd_target) + + ob_targetx.append(path_target.x[1]) + ob_targety.append(path_target.y[1]) + + ob_target = np.array([ob_targetx,ob_targety]) + + + path = frenet_optimal_planning( + csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target) + + del ob_targetx[-1] + del ob_targety[-1] + + s0 = path.s[1] + c_d = path.d[1] + c_d_d = path.d_d[1] + c_d_dd = path.d_dd[1] + c_speed = path.s_d[1] + + s0_target = path_target.s[1] + c_d_target = path_target.d[1] + c_d_d_target = path_target.d_d[1] + c_d_dd_target = path_target.d_dd[1] + c_speed_target = path_target.s_d[1] + + + if(path_target.s_d[1] >= 11.0): + c_speed_target = 10.0 + + if (np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0) and (np.hypot(path_target.x[1] - tx_target[-1], path_target.y[1] - ty_target[-1]) <= 1.0): + print("Goal") + break + + if show_animation: # pragma: no cover + plt.cla() + plt.plot(tx, ty) + plt.plot(ob_target[0], ob_target[1], "xk") + plt.plot(path.x[1:], path.y[1:], "-or") + plt.plot(path.x[1], path.y[1], "vc") + plt.plot(path_target.x[1:], path_target.y[1:], "-ob") + plt.plot(path_target.x[1], path_target.y[1], "vc") + plt.xlim(path.x[1] - area, path.x[1] + area) + plt.ylim(path.y[1] - area, path.y[1] + area) + plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4] + " " + "vt[km/h]:" + str(c_speed_target * 3.6)[0:4]) + plt.grid(True) + plt.pause(0.0001) + + # stop = time.time() + # duration = stop-start + # print(duration) + + print("Finish") + if show_animation: # pragma: no cover + plt.grid(True) + plt.pause(0.0001) + plt.show() + + +if __name__ == '__main__': + main(sys.argv[1]) diff --git a/PathPlanning/FrenetOptimalTrajectory/racing_line.py b/PathPlanning/FrenetOptimalTrajectory/racing_line.py new file mode 100644 index 0000000000..fc1fdc9c2d --- /dev/null +++ b/PathPlanning/FrenetOptimalTrajectory/racing_line.py @@ -0,0 +1,80 @@ +import sys +from math import sqrt +import math +import os +import numpy as np +import json + + +class RacingLine: + + def json_parser(self, json_file): + + race_x = [] + race_y = [] + ins_x = [] + ins_y = [] + out_x = [] + out_y = [] + + with open(json_file) as data_file: + data = json.loads(data_file.read()) + o = data['Outside'] + t = data['Inside'] + p = data['Racing'] + for i in range(len(t)): + d = t[i] + n = d[0] + m = d[1] + ins_x.append(n) + ins_y.append(m) + + for j in range(len(o)): + c = o[j] + x = c[0] + y = c[1] + out_x.append(x) + out_y.append(y) + + for e in range(len(p)): + if e%20 != 0: + z = p[e] + g = z[0] + h = z[1] + race_x.append(g) + race_y.append(h) + + + rx = np.array(race_x) + + return race_x, race_y, ins_x, ins_y, out_x, out_y + + def curved_abscissa(self): + sum_partial = [] + c_a = [0] * len(self.race_x) + + for i in range(len(self.race_x)): + if(i == 0): + c_a[0] = 0 + else: + c_a[i] = sqrt(pow(self.race_x[i] - self.race_x[i-1],2)+pow(self.race_y[i] - self.race_y[i-1],2)) + c_a[i-1] + + return c_a + + + + def print_usage(self): + print('') + +def main(json_file): + rc = RacingLine() + rc.json_parser(json_file) + rc.curved_abscissa() + + + +if __name__ == '__main__': + if not len(sys.argv) == 2: + print_usage() + else: + main(sys.argv[1]) diff --git a/PathPlanning/FrenetOptimalTrajectory/track.json b/PathPlanning/FrenetOptimalTrajectory/track.json new file mode 100644 index 0000000000..db2e361821 --- /dev/null +++ b/PathPlanning/FrenetOptimalTrajectory/track.json @@ -0,0 +1,19864 @@ +{"Inside": [ + [ + 18.041240027146795, + 61.5672178323233 + ], + [ + 18.540132932009278, + 61.606139632913745 + ], + [ + 19.03304531395716, + 61.521961650214955 + ], + [ + 19.521440043495968, + 61.41241500313734 + ], + [ + 19.99444133532521, + 61.248884299733973 + ], + [ + 20.462763908454185, + 61.067792827532962 + ], + [ + 20.959610773381321, + 61.00833459938476 + ], + [ + 21.4600621967377, + 60.981607829349755 + ], + [ + 21.95877043036716, + 60.948191225520311 + ], + [ + 22.423921209751818, + 60.760288040657159 + ], + [ + 22.884548696910368, + 60.559913306727232 + ], + [ + 23.351085847420876, + 60.3764492368257 + ], + [ + 23.81330714586646, + 60.180152067484748 + ], + [ + 24.274992730323852, + 59.976903921319447 + ], + [ + 24.736781232529474, + 59.774695041777314 + ], + [ + 25.205007846491, + 59.598591739028549 + ], + [ + 25.678389144983527, + 59.423500788924912 + ], + [ + 26.154096045065995, + 59.264097293875011 + ], + [ + 26.638410545873644, + 59.110839827336328 + ], + [ + 27.127636088130114, + 58.973894495103757 + ], + [ + 27.619835081665936, + 58.843272153138535 + ], + [ + 28.112141313733833, + 58.708518356484213 + ], + [ + 28.608397179987612, + 58.58874655869149 + ], + [ + 29.0992031013781, + 58.476371447086393 + ], + [ + 29.592367985963669, + 58.361306089314368 + ], + [ + 30.079521248082145, + 58.238680646454263 + ], + [ + 30.56719200348083, + 58.116840878275951 + ], + [ + 31.060826772824285, + 57.99631953526459 + ], + [ + 31.548925378917058, + 57.868933549434217 + ], + [ + 32.040410175457588, + 57.744577538941662 + ], + [ + 32.533317333667654, + 57.627085241457074 + ], + [ + 33.024885170210617, + 57.510263088748005 + ], + [ + 33.5146741756995, + 57.37785818896257 + ], + [ + 34.008445762764019, + 57.244508640819816 + ], + [ + 34.504896273866152, + 57.116737659371729 + ], + [ + 35.001157848728994, + 56.983413686871529 + ], + [ + 35.496194370694, + 56.844741623190679 + ], + [ + 35.988500208097996, + 56.698895207175056 + ], + [ + 36.480312059535549, + 56.550188234208541 + ], + [ + 36.970335104344244, + 56.396063862535108 + ], + [ + 37.44841153531663, + 56.245405936933956 + ], + [ + 37.931030006338254, + 56.09250442658994 + ], + [ + 38.41663997303899, + 55.936694849240084 + ], + [ + 38.898883539228919, + 55.781515786211479 + ], + [ + 39.373559537764471, + 55.62211354924024 + ], + [ + 39.857783568458473, + 55.455974026728335 + ], + [ + 40.341216644879822, + 55.292254870311822 + ], + [ + 40.818938714950107, + 55.135491578037772 + ], + [ + 41.300392235439126, + 54.9828114346474 + ], + [ + 41.784500705661081, + 54.827728164860005 + ], + [ + 42.264199542480533, + 54.675890146069186 + ], + [ + 42.753720679462937, + 54.522006582259415 + ], + [ + 43.239759959262287, + 54.379668993080791 + ], + [ + 43.731539731646713, + 54.242679614298723 + ], + [ + 44.216447390979084, + 54.108871681104631 + ], + [ + 44.707006044719741, + 53.975992440843868 + ], + [ + 45.199594613982342, + 53.840634572706463 + ], + [ + 45.684515471730172, + 53.701202281783345 + ], + [ + 46.175657648142547, + 53.574853180042659 + ], + [ + 46.667341067306126, + 53.45218307515924 + ], + [ + 47.158074311796788, + 53.333958012041215 + ], + [ + 47.651878498375872, + 53.227930638698425 + ], + [ + 48.141823620088978, + 53.120790395246821 + ], + [ + 48.640197305981921, + 53.030267729656089 + ], + [ + 49.132918852571734, + 52.941997557893487 + ], + [ + 49.636210614794813, + 52.928513908502914 + ], + [ + 50.135026325279576, + 52.963548683226747 + ], + [ + 50.628381382295238, + 53.060935283225028 + ], + [ + 51.1099162885146, + 53.202323417463909 + ], + [ + 51.5684541698286, + 53.402954621475025 + ], + [ + 52.022035690838521, + 53.625681173162931 + ], + [ + 52.474302245358061, + 53.8502456525502 + ], + [ + 52.9271497698659, + 54.082410670780831 + ], + [ + 53.375562803698955, + 54.32035177475619 + ], + [ + 53.822658476849192, + 54.553213764280876 + ], + [ + 54.266512769533982, + 54.793247254734759 + ], + [ + 54.711551243885822, + 55.032877139162338 + ], + [ + 55.166859138259767, + 55.266904787559007 + ], + [ + 55.615491309593068, + 55.489784861012822 + ], + [ + 56.075967988532582, + 55.711200279688562 + ], + [ + 56.5307618345017, + 55.939326258774479 + ], + [ + 56.978584663671562, + 56.173368685205276 + ], + [ + 57.428188449594771, + 56.397551193252248 + ], + [ + 57.892204151043558, + 56.616631612027092 + ], + [ + 58.352652949886291, + 56.830131639319241 + ], + [ + 58.807494420141509, + 57.04130701770454 + ], + [ + 59.269757066988724, + 57.258671662293366 + ], + [ + 59.725720189922455, + 57.473307353364994 + ], + [ + 60.185602660997525, + 57.692126562933616 + ], + [ + 60.639322354822291, + 57.915629283669389 + ], + [ + 61.089284485248612, + 58.135586133618339 + ], + [ + 61.554979488436075, + 58.3565360036978 + ], + [ + 62.007581091702079, + 58.570796129857143 + ], + [ + 62.458511511564375, + 58.791810419892514 + ], + [ + 62.920331010951656, + 59.022123712066545 + ], + [ + 63.37039762993814, + 59.241558960851329 + ], + [ + 63.822325772327325, + 59.46039603885648 + ], + [ + 64.277329734000091, + 59.678149172356449 + ], + [ + 64.737374234319489, + 59.895048951331567 + ], + [ + 65.196940214569835, + 60.114269827626913 + ], + [ + 65.659806836608283, + 60.328576577413159 + ], + [ + 66.127005519163163, + 60.538004324548325 + ], + [ + 66.592671970253775, + 60.75107141953346 + ], + [ + 67.059509312201314, + 60.96528814718188 + ], + [ + 67.526409088211423, + 61.183214547521644 + ], + [ + 67.992840633954444, + 61.403983458981827 + ], + [ + 68.4582304352355, + 61.627465816130162 + ], + [ + 68.909312284684063, + 61.846790334596363 + ], + [ + 69.3594008420431, + 62.0700729563248 + ], + [ + 69.806501956230832, + 62.302641374410761 + ], + [ + 70.249342957858559, + 62.543005133516388 + ], + [ + 70.691523740136176, + 62.784944433349743 + ], + [ + 71.133445678418482, + 63.029978135154145 + ], + [ + 71.57508854325738, + 63.278326873230839 + ], + [ + 72.015715302383285, + 63.527882561978778 + ], + [ + 72.456618380112616, + 63.780938429709224 + ], + [ + 72.895479180950076, + 64.038670545254348 + ], + [ + 73.332951753801041, + 64.297905276825588 + ], + [ + 73.770231781639851, + 64.55708843143772 + ], + [ + 74.207046976255228, + 64.816907384607049 + ], + [ + 74.643627060357758, + 65.075198424811532 + ], + [ + 75.082077076113109, + 65.331268147816544 + ], + [ + 75.5218821107083, + 65.585408586875744 + ], + [ + 75.9639310360089, + 65.836309406249626 + ], + [ + 76.404926727039324, + 66.082608592367933 + ], + [ + 76.855715281904, + 66.333723554661518 + ], + [ + 77.305610355339809, + 66.5837463484805 + ], + [ + 77.747433815293633, + 66.827398592775154 + ], + [ + 78.193248100615321, + 67.06991393345416 + ], + [ + 78.638609398279428, + 67.309037608521336 + ], + [ + 79.084521391231988, + 67.54598298349768 + ], + [ + 79.533663460017138, + 67.780486147232622 + ], + [ + 79.9830681266752, + 68.01101744581365 + ], + [ + 80.442762258061862, + 68.244946358730786 + ], + [ + 80.899393256055674, + 68.475012871515759 + ], + [ + 81.354605522187413, + 68.6973719538629 + ], + [ + 81.807155388776039, + 68.913244953742819 + ], + [ + 82.2639122196896, + 69.147752572249033 + ], + [ + 82.71208756306163, + 69.386954492194249 + ], + [ + 83.157328542878517, + 69.618585441192636 + ], + [ + 83.606806651337749, + 69.859840468467 + ], + [ + 84.0478577577858, + 70.1053935310645 + ], + [ + 84.494100780545779, + 70.361220055562725 + ], + [ + 84.92735163028587, + 70.623609451453831 + ], + [ + 85.3532211786674, + 70.893759663026231 + ], + [ + 85.778903603451241, + 71.174121530550622 + ], + [ + 86.201490149468469, + 71.4637665463959 + ], + [ + 86.620801896726988, + 71.755992613622453 + ], + [ + 87.034480849309347, + 72.043741568863837 + ], + [ + 87.44059792664342, + 72.340620970992376 + ], + [ + 87.823397087624485, + 72.666714363278942 + ], + [ + 88.185518366259842, + 73.0126268516023 + ], + [ + 88.529535206948836, + 73.380640892801225 + ], + [ + 88.853122919180478, + 73.762741590319067 + ], + [ + 89.141306524206016, + 74.177233319809048 + ], + [ + 89.358319200438288, + 74.633611957536672 + ], + [ + 89.4929656587074, + 75.121866767306216 + ], + [ + 89.550165845648237, + 75.626027007030558 + ], + [ + 89.532622857967638, + 76.128287451001185 + ], + [ + 89.426228713425331, + 76.623185636357761 + ], + [ + 89.231547412218745, + 77.0899659148364 + ], + [ + 89.00986693739209, + 77.53885379083853 + ], + [ + 88.759387209453863, + 77.973174962095456 + ], + [ + 88.486517265491045, + 78.398371056693861 + ], + [ + 88.195064008998344, + 78.804733008266112 + ], + [ + 87.900045579745438, + 79.210770757209858 + ], + [ + 87.584615914793176, + 79.613920466009034 + ], + [ + 87.2631152950637, + 80.012630674451458 + ], + [ + 86.939110795064508, + 80.407780284759752 + ], + [ + 86.62091537904773, + 80.804511441219375 + ], + [ + 86.312629045677923, + 81.203674973787571 + ], + [ + 86.000750769960476, + 81.610011786560847 + ], + [ + 85.6924956762032, + 82.013773817855267 + ], + [ + 85.3923801440287, + 82.4146430616312 + ], + [ + 85.093013326664433, + 82.825227577500428 + ], + [ + 84.794659065420461, + 83.245744973079482 + ], + [ + 84.501719874297407, + 83.6587673823403 + ], + [ + 84.206113786931454, + 84.077281582629467 + ], + [ + 83.9186088572631, + 84.490598700605915 + ], + [ + 83.628682514457253, + 84.9093756477736 + ], + [ + 83.333867482822072, + 85.3315616479112 + ], + [ + 83.047727383104984, + 85.7448626683359 + ], + [ + 82.762909257982514, + 86.16484356588785 + ], + [ + 82.478738878930159, + 86.591305897894912 + ], + [ + 82.2039756378267, + 87.010014533595609 + ], + [ + 81.927723228049217, + 87.4336175104722 + ], + [ + 81.652192715399977, + 87.863900238397036 + ], + [ + 81.376282500124219, + 88.299971039561939 + ], + [ + 81.106950064456484, + 88.723186226040426 + ], + [ + 80.8312060435251, + 89.148592917239327 + ], + [ + 80.55541254273767, + 89.578576832024012 + ], + [ + 80.280885475119561, + 90.014174503247 + ], + [ + 80.01502248713156, + 90.437852712713592 + ], + [ + 79.745070114259008, + 90.865562793350463 + ], + [ + 79.476549613694488, + 91.299132061062437 + ], + [ + 79.20940295789346, + 91.7367107167942 + ], + [ + 78.941801603804578, + 92.179218241006808 + ], + [ + 78.67882424522233, + 92.607640808306485 + ], + [ + 78.414326412884691, + 93.038950096709215 + ], + [ + 78.149532332305, + 93.472225268013943 + ], + [ + 77.886994569344353, + 93.910887642239771 + ], + [ + 77.621501302766589, + 94.35062699793086 + ], + [ + 77.3517462542476, + 94.78968248962326 + ], + [ + 77.084217852076335, + 95.233331202448426 + ], + [ + 76.827722944814226, + 95.662891238735739 + ], + [ + 76.569603076202029, + 96.095068529482418 + ], + [ + 76.310175642163884, + 96.52766450931459 + ], + [ + 76.05354778695137, + 96.9645480336336 + ], + [ + 75.797630153143373, + 97.403344385049692 + ], + [ + 75.541158112437628, + 97.845428283574591 + ], + [ + 75.281566623370438, + 98.286391410936815 + ], + [ + 75.022118469810749, + 98.729207201963334 + ], + [ + 74.762921360671626, + 99.172850821423836 + ], + [ + 74.50480815885345, + 99.619251658147093 + ], + [ + 74.2435889903587, + 100.0643245481443 + ], + [ + 73.979405677681413, + 100.50871141218397 + ], + [ + 73.716297431410624, + 100.95519084237577 + ], + [ + 73.465710972380961, + 101.38824025109666 + ], + [ + 73.21484435278353, + 101.82251694864883 + ], + [ + 72.960323362198039, + 102.25592488316789 + ], + [ + 72.704113761121889, + 102.69091523798006 + ], + [ + 72.449813311803183, + 103.12922213873063 + ], + [ + 72.194861984933965, + 103.56855538690108 + ], + [ + 71.937569147641739, + 104.00769188005438 + ], + [ + 71.680429543567726, + 104.44917939203883 + ], + [ + 71.424170793147638, + 104.89393192936851 + ], + [ + 71.171885254466176, + 105.34053738614472 + ], + [ + 70.920595707766509, + 105.78573026340466 + ], + [ + 70.6682651496037, + 106.23097308741829 + ], + [ + 70.415709557741764, + 106.6769432672791 + ], + [ + 70.162065360548709, + 107.12313928714214 + ], + [ + 69.908074380050536, + 107.5691641997896 + ], + [ + 69.6553111304129, + 108.0152271719556 + ], + [ + 69.406155922327471, + 108.464251132163 + ], + [ + 69.16120124281106, + 108.91623942822612 + ], + [ + 68.917867555751315, + 109.36985664621365 + ], + [ + 68.674149871536613, + 109.82334162320096 + ], + [ + 68.430254671795581, + 110.27532366057112 + ], + [ + 68.185698111719773, + 110.72794403418324 + ], + [ + 67.937973965453267, + 111.17907706186389 + ], + [ + 67.682937656372687, + 111.62576780430253 + ], + [ + 67.420326295853272, + 112.06922794844545 + ], + [ + 67.151329062556712, + 112.50923634738869 + ], + [ + 66.87593993011825, + 112.94643320634677 + ], + [ + 66.592065238143121, + 113.37866082031837 + ], + [ + 66.295487412735355, + 113.8031695851393 + ], + [ + 65.989753352823428, + 114.22299653514655 + ], + [ + 65.68110519183567, + 114.63888943950337 + ], + [ + 65.366758127045784, + 115.0512778137055 + ], + [ + 65.043980268511987, + 115.4577446597683 + ], + [ + 64.715996592294687, + 115.86014345491228 + ], + [ + 64.385433694977323, + 116.26116096512705 + ], + [ + 64.050413943338484, + 116.65828036473229 + ], + [ + 63.708236529620621, + 117.0509601091433 + ], + [ + 63.375511200995938, + 117.42425049293763 + ], + [ + 63.039865590032448, + 117.79481427159277 + ], + [ + 62.699524972306676, + 118.16149784498602 + ], + [ + 62.353886768737624, + 118.52332365743048 + ], + [ + 62.002299938736918, + 118.88125749384514 + ], + [ + 61.649831968291956, + 119.23667648666157 + ], + [ + 61.298382159775933, + 119.59344257836001 + ], + [ + 60.946210651952818, + 119.95249761065637 + ], + [ + 60.591702840476763, + 120.31437075817041 + ], + [ + 60.235784629519728, + 120.67899746569333 + ], + [ + 59.880451043690222, + 121.04797911413455 + ], + [ + 59.52503388553793, + 121.41967377783567 + ], + [ + 59.169541841962754, + 121.78786168575486 + ], + [ + 58.816892792760349, + 122.1495942204632 + ], + [ + 58.4668173021515, + 122.50831951072638 + ], + [ + 58.107222501749689, + 122.87952548577378 + ], + [ + 57.750336162416829, + 123.24758043493249 + ], + [ + 57.396850160010608, + 123.61636632073578 + ], + [ + 57.051674984922734, + 123.98675161503817 + ], + [ + 56.710328740539737, + 124.35606546099359 + ], + [ + 56.358652294914336, + 124.73686671859521 + ], + [ + 56.008977104247613, + 125.11485194372125 + ], + [ + 55.662777468108786, + 125.49010084129412 + ], + [ + 55.318761930983818, + 125.86631294607045 + ], + [ + 54.975837733868282, + 126.25143276815193 + ], + [ + 54.6322340226289, + 126.63624301139839 + ], + [ + 54.290608472181496, + 127.00996454792588 + ], + [ + 53.942330486103657, + 127.39314053233953 + ], + [ + 53.598876920393344, + 127.77559040127922 + ], + [ + 53.25902538807366, + 128.15728841668718 + ], + [ + 52.925739858896563, + 128.53752051404976 + ], + [ + 52.5874386397692, + 128.93066998895188 + ], + [ + 52.253874180953787, + 129.32173687317894 + ], + [ + 51.925622399366468, + 129.70578298369475 + ], + [ + 51.596556788065563, + 130.09469041222081 + ], + [ + 51.269170545059687, + 130.48998832307169 + ], + [ + 50.94707023007561, + 130.8936500783 + ], + [ + 50.642960440192958, + 131.29211492901013 + ], + [ + 50.345355481181109, + 131.70005699329352 + ], + [ + 50.062695010973435, + 132.11500189128262 + ], + [ + 49.78695374326675, + 132.55044929258494 + ], + [ + 49.5273186321934, + 132.98339054200503 + ], + [ + 49.280339919314592, + 133.4297838738064 + ], + [ + 49.0557980727692, + 133.88236750873458 + ], + [ + 48.847638818660791, + 134.35301134700521 + ], + [ + 48.656476837372935, + 134.82003917896091 + ], + [ + 48.479702429408363, + 135.288481260017 + ], + [ + 48.31881178638502, + 135.77456657536445 + ], + [ + 48.172519753618765, + 136.26777793845648 + ], + [ + 48.029565128486091, + 136.76047899104594 + ], + [ + 47.897718176792068, + 137.24808489421858 + ], + [ + 47.7728394455754, + 137.74473058126142 + ], + [ + 47.657692720947395, + 138.24070962613055 + ], + [ + 47.550619162905782, + 138.73003066223225 + ], + [ + 47.449128087703109, + 139.2226919217666 + ], + [ + 47.357690696527939, + 139.72855689781912 + ], + [ + 47.282272520212082, + 140.22368881805815 + ], + [ + 47.203247002144209, + 140.71841103178738 + ], + [ + 47.116690391715515, + 141.21634448589234 + ], + [ + 47.0382261563089, + 141.72187380837161 + ], + [ + 46.982303865039583, + 142.22237333158128 + ], + [ + 46.948416983939509, + 142.73065655801159 + ], + [ + 46.933269033828687, + 143.23525340889412 + ], + [ + 46.9356973096146, + 143.74383435244553 + ], + [ + 46.963294287493873, + 144.25075670850876 + ], + [ + 47.014980324457127, + 144.7535587194696 + ], + [ + 47.106066546596445, + 145.24796303950976 + ], + [ + 47.235971606844124, + 145.73497956575704 + ], + [ + 47.394110967737824, + 146.22126005419659 + ], + [ + 47.575861289308143, + 146.69553272737559 + ], + [ + 47.7648138270856, + 147.16347674924123 + ], + [ + 47.959466041985763, + 147.63144234634046 + ], + [ + 48.170125600420306, + 148.09871570002457 + ], + [ + 48.386084410814561, + 148.56350681696222 + ], + [ + 48.6065876023541, + 149.02494728877511 + ], + [ + 48.823490127987, + 149.48042454424603 + ], + [ + 49.039055302734589, + 149.93952306143135 + ], + [ + 49.26276461135938, + 150.39978046884679 + ], + [ + 49.488748318212934, + 150.85473821868726 + ], + [ + 49.712079437186411, + 151.3141654131345 + ], + [ + 49.935015859122409, + 151.76482871497223 + ], + [ + 50.164812525858636, + 152.21553565282073 + ], + [ + 50.410026841001539, + 152.66686655280043 + ], + [ + 50.649214471514881, + 153.113588882425 + ], + [ + 50.895800540418946, + 153.55907043034767 + ], + [ + 51.146972619740687, + 153.99844515758079 + ], + [ + 51.406540041831832, + 154.43590874829545 + ], + [ + 51.667833812280179, + 154.86570046013975 + ], + [ + 51.9360244673357, + 155.28824647731142 + ], + [ + 52.2170412944724, + 155.71010683467137 + ], + [ + 52.514133552173135, + 156.12198871014408 + ], + [ + 52.825717414387405, + 156.52567384747403 + ], + [ + 53.15511717040696, + 156.91564201057895 + ], + [ + 53.5006198348936, + 157.29677286058649 + ], + [ + 53.848817643804793, + 157.65736396366967 + ], + [ + 54.213024679557265, + 158.00476148137068 + ], + [ + 54.595035209506221, + 158.34339420633282 + ], + [ + 54.980902860669296, + 158.66589376283946 + ], + [ + 55.379092401693967, + 158.98342502091194 + ], + [ + 55.780565611689227, + 159.28192811240746 + ], + [ + 56.194100732563889, + 159.57051715434628 + ], + [ + 56.620564236457639, + 159.84738205624524 + ], + [ + 57.060842736752384, + 160.10902878491561 + ], + [ + 57.497376135019856, + 160.35542809039424 + ], + [ + 57.942367861946813, + 160.59148425859934 + ], + [ + 58.39693630553748, + 160.81470791666771 + ], + [ + 58.8615363532993, + 161.02878151022171 + ], + [ + 59.331241135520813, + 161.24237744780481 + ], + [ + 59.790922220607747, + 161.45184445664182 + ], + [ + 60.257246118051654, + 161.66168072110844 + ], + [ + 60.725961014569229, + 161.87379204638026 + ], + [ + 61.194810074932832, + 162.09024310195193 + ], + [ + 61.655405325885, + 162.29282834602566 + ], + [ + 62.1227655715772, + 162.49076133495265 + ], + [ + 62.59096028738437, + 162.69281869548698 + ], + [ + 63.062060912353814, + 162.89060779348097 + ], + [ + 63.538018192643925, + 163.08327686121271 + ], + [ + 64.018189548295538, + 163.27418533425814 + ], + [ + 64.486505874284632, + 163.45171273126405 + ], + [ + 64.9590816280783, + 163.62410701433939 + ], + [ + 65.444787252307549, + 163.80017693654298 + ], + [ + 65.921988753653679, + 163.9789477954167 + ], + [ + 66.394558726685631, + 164.16020626280903 + ], + [ + 66.868508414524641, + 164.34592339175279 + ], + [ + 67.33527117523991, + 164.52953770267047 + ], + [ + 67.803759510648263, + 164.71430171159582 + ], + [ + 68.269504967321566, + 164.9015901870963 + ], + [ + 68.730663731667178, + 165.09500899894255 + ], + [ + 69.190332141995981, + 165.29386648294425 + ], + [ + 69.650493469902543, + 165.49604753440747 + ], + [ + 70.11004530749203, + 165.69956708047786 + ], + [ + 70.569446497088222, + 165.9055922439488 + ], + [ + 71.02782748827822, + 166.11660829943858 + ], + [ + 71.484051021463, + 166.33458633472679 + ], + [ + 71.936740137317074, + 166.56034748079432 + ], + [ + 72.385069433058888, + 166.79370257459229 + ], + [ + 72.831543621719121, + 167.03336203369545 + ], + [ + 73.272881636372, + 167.28029229119815 + ], + [ + 73.7076007282305, + 167.538768706867 + ], + [ + 74.138634701804293, + 167.80466606128931 + ], + [ + 74.566014325108227, + 168.07456411319438 + ], + [ + 74.988579120056528, + 168.35146546439685 + ], + [ + 75.40597813249552, + 168.63808450704846 + ], + [ + 75.818040051683951, + 168.933584688231 + ], + [ + 76.225208367427186, + 169.23653011206497 + ], + [ + 76.625538490455128, + 169.5484203115727 + ], + [ + 77.0248627585658, + 169.86200362874391 + ], + [ + 77.422350339742266, + 170.1764438288503 + ], + [ + 77.808923778588138, + 170.49787698542579 + ], + [ + 78.1968584735625, + 170.83397857567385 + ], + [ + 78.5940290059126, + 171.16024552490208 + ], + [ + 78.993534711962184, + 171.46264385547082 + ], + [ + 79.404729554097656, + 171.75671773927218 + ], + [ + 79.8290296293925, + 172.05241667968173 + ], + [ + 80.239169907095359, + 172.34580572554219 + ], + [ + 80.65076211939288, + 172.63157618878046 + ], + [ + 81.0706937380559, + 172.90662558031303 + ], + [ + 81.4963526304391, + 173.18097355921827 + ], + [ + 81.933352292564877, + 173.44724181844546 + ], + [ + 82.377403446466857, + 173.7056014226869 + ], + [ + 82.8161277762303, + 173.9704451324003 + ], + [ + 83.252225205009708, + 174.24288381367697 + ], + [ + 83.689614904680084, + 174.51690284724114 + ], + [ + 84.127568744329139, + 174.79083951749271 + ], + [ + 84.563830514972253, + 175.06917031154714 + ], + [ + 84.984264370159607, + 175.34237309534493 + ], + [ + 85.404310878446168, + 175.61843459934528 + ], + [ + 85.823054684189827, + 175.89823893011149 + ], + [ + 86.237661285260984, + 176.18359551854803 + ], + [ + 86.650791189454225, + 176.47336536539893 + ], + [ + 87.065821634222289, + 176.76033099140329 + ], + [ + 87.482298533319238, + 177.04543312768939 + ], + [ + 87.898865958249871, + 177.33253841229075 + ], + [ + 88.314154518629181, + 177.62197707265136 + ], + [ + 88.730289341530423, + 177.91103803260674 + ], + [ + 89.147222472288234, + 178.19786472411155 + ], + [ + 89.558949539339679, + 178.48326427147777 + ], + [ + 89.97701312331354, + 178.77873116858874 + ], + [ + 90.393852323529, + 179.06896897930818 + ], + [ + 90.812724651402888, + 179.3515559609346 + ], + [ + 91.229702191283479, + 179.6299942568817 + ], + [ + 91.657053051804127, + 179.9140477604175 + ], + [ + 92.083906076845054, + 180.19224742523946 + ], + [ + 92.507488956428631, + 180.46779025565593 + ], + [ + 92.926592483697561, + 180.74083787369418 + ], + [ + 93.354280437425771, + 181.02069209061096 + ], + [ + 93.7796303067661, + 181.29509562624432 + ], + [ + 94.20063673994963, + 181.56512077089278 + ], + [ + 94.628528819085929, + 181.84446490287169 + ], + [ + 95.05431576461207, + 182.11842154390484 + ], + [ + 95.475781963574477, + 182.38981447234485 + ], + [ + 95.900665542036108, + 182.66820708072999 + ], + [ + 96.323689599810265, + 182.9467549046243 + ], + [ + 96.748470480494845, + 183.23362308138931 + ], + [ + 97.168932352600109, + 183.5186581749366 + ], + [ + 97.582307085151058, + 183.80125160465875 + ], + [ + 97.989390544586669, + 184.10141968640838 + ], + [ + 98.391671021906333, + 184.39855803907454 + ], + [ + 98.795925764406419, + 184.69735889831031 + ], + [ + 99.1997773530848, + 185.00445801347829 + ], + [ + 99.6088278031915, + 185.30812652578041 + ], + [ + 100.01658111161957, + 185.61008125024603 + ], + [ + 100.42304352296817, + 185.90346631139693 + ], + [ + 100.83063427805075, + 186.20607007084615 + ], + [ + 101.23798361619892, + 186.50845152065773 + ], + [ + 101.63577494129982, + 186.82182079125215 + ], + [ + 102.03355603491569, + 187.13361189750651 + ], + [ + 102.46815914637713, + 187.38690036780341 + ], + [ + 102.89464088145465, + 187.64679781317011 + ], + [ + 103.2502888412413, + 188.00299561538978 + ], + [ + 103.6517880934864, + 188.30337342394589 + ], + [ + 103.98191683979326, + 188.67950660258566 + ], + [ + 104.35131312966341, + 189.01643356038125 + ], + [ + 104.76269282963949, + 189.30380816185874 + ], + [ + 105.17182239743269, + 189.59570669598475 + ], + [ + 105.58769715378891, + 189.87887031145183 + ], + [ + 106.02255967705015, + 190.13624292082 + ], + [ + 106.45228045659836, + 190.39732682261314 + ], + [ + 106.89350500589593, + 190.65434107973528 + ], + [ + 107.33313246764497, + 190.89673991759116 + ], + [ + 107.7700758952099, + 191.14234343574961 + ], + [ + 108.20674982751088, + 191.40108378529993 + ], + [ + 108.64099024212392, + 191.65078778987453 + ], + [ + 109.07892146073331, + 191.89795189318096 + ], + [ + 109.5104675867988, + 192.15422475972747 + ], + [ + 109.95255612428521, + 192.406347609434 + ], + [ + 110.40370269770287, + 192.64711017255581 + ], + [ + 110.85377263540055, + 192.88126945013227 + ], + [ + 111.30266585891054, + 193.10771249972947 + ], + [ + 111.75932514392427, + 193.34448271476782 + ], + [ + 112.20732050426108, + 193.58910123984646 + ], + [ + 112.65104329722406, + 193.82215452064665 + ], + [ + 113.1000668313185, + 194.05932575413388 + ], + [ + 113.53679401693528, + 194.30334113355366 + ], + [ + 113.97925435235088, + 194.55488107183925 + ], + [ + 114.41318155063483, + 194.80566175325257 + ], + [ + 114.84728363001183, + 195.0702391145355 + ], + [ + 115.27966714210673, + 195.3490078720215 + ], + [ + 115.70766454500566, + 195.61692099814292 + ], + [ + 116.14201396650954, + 195.88796341228036 + ], + [ + 116.56438791360178, + 196.15596781854481 + ], + [ + 116.98939238871142, + 196.43031963255805 + ], + [ + 117.41943894505691, + 196.71081961416599 + ], + [ + 117.83884092190048, + 196.98577019125179 + ], + [ + 118.26140659842575, + 197.26555940422023 + ], + [ + 118.68514106368602, + 197.55190542341035 + ], + [ + 119.11191726959999, + 197.84176865686584 + ], + [ + 119.52547659871411, + 198.12501634421199 + ], + [ + 119.95161576265164, + 198.42075490494551 + ], + [ + 120.37011014773491, + 198.71362615506408 + ], + [ + 120.78188940378082, + 199.00353152236147 + ], + [ + 121.19041944595894, + 199.29366185455308 + ], + [ + 121.60897310934683, + 199.59742979648544 + ], + [ + 122.02246469856678, + 199.90067692266348 + ], + [ + 122.43623999696129, + 200.20370985055024 + ], + [ + 122.85230202279539, + 200.51206631097878 + ], + [ + 123.26254670700779, + 200.82259674946991 + ], + [ + 123.66216396732418, + 201.12873139050257 + ], + [ + 124.06702944668199, + 201.43906243305418 + ], + [ + 124.46577649639121, + 201.75298188121204 + ], + [ + 124.85747670012366, + 202.07077924211083 + ], + [ + 125.24282660400097, + 202.38917837306369 + ], + [ + 125.62707786885136, + 202.71403694229733 + ], + [ + 126.01900082622697, + 203.04712944211619 + ], + [ + 126.4098394248723, + 203.37267299744659 + ], + [ + 126.79587002801601, + 203.69848860963853 + ], + [ + 127.17514967453428, + 204.02435818846641 + ], + [ + 127.56336872650128, + 204.35821598109283 + ], + [ + 127.94392509317973, + 204.68849673864344 + ], + [ + 128.32770524028808, + 205.03179421227975 + ], + [ + 128.70064546314211, + 205.36602851894287 + ], + [ + 129.07287345015757, + 205.70579457383769 + ], + [ + 129.43856370492961, + 206.04898761842708 + ], + [ + 129.80629108045065, + 206.3993236045512 + ], + [ + 130.16025763635849, + 206.76135536116038 + ], + [ + 130.47989763940808, + 207.15347056780578 + ], + [ + 130.775896738172, + 207.56396864629605 + ], + [ + 131.03954003213471, + 207.9905478015925 + ], + [ + 131.26778631393569, + 208.44544708158651 + ], + [ + 131.42964345145657, + 208.92176431231627 + ], + [ + 131.55108206355, + 209.4128867952623 + ], + [ + 131.59323659915413, + 209.91306298438931 + ], + [ + 131.60581372092429, + 210.42050564164768 + ], + [ + 131.58168934451217, + 210.92350891033794 + ], + [ + 131.55959370266743, + 211.42659614886512 + ], + [ + 131.53359532576894, + 211.93098316112381 + ], + [ + 131.42370982973137, + 212.42673142714102 + ], + [ + 131.25839595394547, + 212.90574349688262 + ], + [ + 131.05059527091439, + 213.36445198825567 + ], + [ + 130.78251969324722, + 213.79428802735777 + ], + [ + 130.476904761725, + 214.19872263939845 + ], + [ + 130.14311377016591, + 214.57591947592198 + ], + [ + 129.79727654090183, + 214.937664367678 + ], + [ + 129.44685748448543, + 215.30501075563859 + ], + [ + 129.08408366908446, + 215.66629095969802 + ], + [ + 128.72375897598428, + 216.01594876982807 + ], + [ + 128.36013288895305, + 216.36189619043847 + ], + [ + 128.00821113781652, + 216.71882731671752 + ], + [ + 127.66121377099283, + 217.0968742164753 + ], + [ + 127.31563867028224, + 217.46661205237211 + ], + [ + 126.9728598209046, + 217.84196115116868 + ], + [ + 126.64218389078474, + 218.22504907359334 + ], + [ + 126.31510387839893, + 218.609215211294 + ], + [ + 125.99533167753064, + 218.99918369893513 + ], + [ + 125.68283604579152, + 219.40101525079629 + ], + [ + 125.37326564662675, + 219.80445357165337 + ], + [ + 125.07124263839255, + 220.20680569727659 + ], + [ + 124.76383940083844, + 220.617289483654 + ], + [ + 124.45979748979447, + 221.01785958171277 + ], + [ + 124.15797722596695, + 221.42679088788222 + ], + [ + 123.86942155007478, + 221.83686818204527 + ], + [ + 123.57545360399553, + 222.24340844435352 + ], + [ + 123.27727001656467, + 222.64720543261012 + ], + [ + 122.98919994792263, + 223.059470824894 + ], + [ + 122.69578723848954, + 223.47565646917946 + ], + [ + 122.40590094044498, + 223.88583790729311 + ], + [ + 122.11628037017458, + 224.29728202976202 + ], + [ + 121.82123401324596, + 224.70886307867809 + ], + [ + 121.53183717356139, + 225.12748439441006 + ], + [ + 121.24315811623885, + 225.54855052369553 + ], + [ + 120.94874688465909, + 225.96693907118268 + ], + [ + 120.64757466880916, + 226.38002588607833 + ], + [ + 120.34344542591543, + 226.77867212875682 + ], + [ + 120.03306306734073, + 227.17179960041523 + ], + [ + 119.72932221815329, + 227.57563815840291 + ], + [ + 119.41339189175154, + 227.97210998250245 + ], + [ + 119.08803582094926, + 228.35491673526309 + ], + [ + 118.75315624336854, + 228.72866017691831 + ], + [ + 118.41749888185683, + 229.0997048399874 + ], + [ + 118.0938099528066, + 229.48523325553418 + ], + [ + 117.83711582944433, + 229.91560333314735 + ], + [ + 117.39120071117553, + 230.13102230490463 + ], + [ + 116.89924351756876, + 230.21118183028966 + ], + [ + 116.60316594352183, + 230.61477912143209 + ], + [ + 117.06807912657042, + 230.43244504064418 + ], + [ + 117.45514431178471, + 230.11757875803338 + ], + [ + 117.1338922353852, + 230.47268159995531 + ], + [ + 116.70050632730721, + 230.72682960735068 + ], + [ + 116.31216509521028, + 231.03992767644809 + ], + [ + 116.07570382691938, + 231.47769239554557 + ], + [ + 115.79909963665567, + 231.90393134628948 + ], + [ + 115.48548149267622, + 232.29458946830741 + ], + [ + 115.18802522488289, + 232.70159709233249 + ], + [ + 114.90244956327835, + 233.11465244865931 + ], + [ + 114.59814400017037, + 233.52011516127206 + ], + [ + 114.31653665119281, + 233.94485773653409 + ], + [ + 114.06547852101684, + 234.38133724470504 + ], + [ + 113.80600500452439, + 234.80964217605998 + ], + [ + 113.54054508266569, + 235.24064913086605 + ], + [ + 113.26058160502214, + 235.66845799390239 + ], + [ + 112.98380518638157, + 236.08875043147472 + ], + [ + 112.69695523589968, + 236.51418080406214 + ], + [ + 112.3998848479945, + 236.93234785902166 + ], + [ + 112.09931025686923, + 237.34242480927159 + ], + [ + 111.78659780037458, + 237.7451080774978 + ], + [ + 111.47699529335317, + 238.14634662164295 + ], + [ + 111.1616233317461, + 238.54192220914121 + ], + [ + 110.84095236855866, + 238.94156391334803 + ], + [ + 110.5131461222083, + 239.3278052250044 + ], + [ + 110.17840027131736, + 239.71907528550884 + ], + [ + 109.84503098008503, + 240.1056660065276 + ], + [ + 109.51922388997761, + 240.48698503940233 + ], + [ + 109.18976039633063, + 240.87531752041804 + ], + [ + 108.85913701663269, + 241.25111827286005 + ], + [ + 108.5249332424214, + 241.62335499276881 + ], + [ + 108.19067162345648, + 242.00013487870794 + ], + [ + 107.85447618578556, + 242.38057900484984 + ], + [ + 107.52342943513808, + 242.75675855528658 + ], + [ + 107.19648824304382, + 243.13868354352383 + ], + [ + 106.86889748994797, + 243.5281534007259 + ], + [ + 106.54031433194406, + 243.9227899034085 + ], + [ + 106.21570696165914, + 244.31237614330794 + ], + [ + 105.89236263091077, + 244.6950345871098 + ], + [ + 105.57086156334681, + 245.08215272160922 + ], + [ + 105.24653243209055, + 245.46519991174634 + ], + [ + 104.91501758251657, + 245.84736391413551 + ], + [ + 104.58174320188159, + 246.23459039881567 + ], + [ + 104.22873971988952, + 246.60695811438689 + ], + [ + 103.87335561763015, + 246.9649839355929 + ], + [ + 103.52993663839632, + 247.33583146594631 + ], + [ + 103.21065280415189, + 247.72120479419579 + ], + [ + 102.89870527631587, + 248.12104668109257 + ], + [ + 102.59075612840567, + 248.53127989980496 + ], + [ + 102.28190309433674, + 248.92577493349293 + ], + [ + 101.97612483561041, + 249.32381961561273 + ], + [ + 101.67736849219173, + 249.72520140535906 + ], + [ + 101.37659572467634, + 250.13466205895395 + ], + [ + 101.09862799922058, + 250.55257144723814 + ], + [ + 100.83746392648584, + 250.98039837820193 + ], + [ + 100.57742332823381, + 251.40765150537146 + ], + [ + 100.30907485240249, + 251.83856026526036 + ], + [ + 100.03748138157825, + 252.25840750771346 + ], + [ + 99.757988631964068, + 252.67689480565358 + ], + [ + 99.469016538262082, + 253.09096790988212 + ], + [ + 99.166264168811324, + 253.4995184891979 + ], + [ + 98.855482993635846, + 253.9053505576089 + ], + [ + 98.542711876054128, + 254.31194177974322 + ], + [ + 98.231966949875911, + 254.70364208381241 + ], + [ + 97.906864075950011, + 255.10046337922853 + ], + [ + 97.590695110146342, + 255.488579655192 + ], + [ + 97.271900546057651, + 255.88379466788467 + ], + [ + 96.946757393970145, + 256.26824627393205 + ], + [ + 96.606640596918368, + 256.6520061404799 + ], + [ + 96.263169822273227, + 257.0206420313051 + ], + [ + 95.905496915228, + 257.38164042342709 + ], + [ + 95.540786643215014, + 257.74228649692964 + ], + [ + 95.185632006813137, + 258.09526029533 + ], + [ + 94.833951242301708, + 258.45090582439906 + ], + [ + 94.485929913249876, + 258.81932119919168 + ], + [ + 94.140546502054178, + 259.18131664299057 + ], + [ + 93.78214110866972, + 259.54329203957042 + ], + [ + 93.400246592557068, + 259.88140688603431 + ], + [ + 93.021199073288031, + 260.20814147200093 + ], + [ + 92.636273312797258, + 260.53356729527417 + ], + [ + 92.249568076201982, + 260.85879059602416 + ], + [ + 91.849068905474041, + 261.16573209622106 + ], + [ + 91.454568975809181, + 261.47956461804284 + ], + [ + 91.0957290293005, + 261.83025225287469 + ], + [ + 90.670560171876232, + 262.078169845435 + ], + [ + 90.246050810168427, + 262.34013558999476 + ], + [ + 89.917187760599447, + 262.72195549673887 + ], + [ + 89.6007948048083, + 263.10934354305653 + ], + [ + 89.247365804118246, + 263.46829091131292 + ], + [ + 88.91457725814854, + 263.83025662299508 + ], + [ + 88.619767758361476, + 264.22092967244089 + ], + [ + 88.320549490554541, + 264.62917491396439 + ], + [ + 88.03352505584671, + 265.0386171324833 + ], + [ + 87.7689421003423, + 265.47084460538434 + ], + [ + 87.485850185588347, + 265.89070335277114 + ], + [ + 87.19625360503, + 266.30604349135979 + ], + [ + 86.912961508113668, + 266.72024587558576 + ], + [ + 86.62297278580364, + 267.12989686402869 + ], + [ + 86.3221336762352, + 267.53801953610957 + ], + [ + 86.018580263789119, + 267.94403958863387 + ], + [ + 85.710965839951143, + 268.35151874027696 + ], + [ + 85.420038214979215, + 268.76314792381362 + ], + [ + 85.12081241691034, + 269.16414462424706 + ], + [ + 84.81896191584552, + 269.56287622493306 + ], + [ + 84.518523304576945, + 269.9804030843913 + ], + [ + 84.222748859666822, + 270.39528339906332 + ], + [ + 83.924374328781568, + 270.80304873799525 + ], + [ + 83.62346761896741, + 271.20259122993644 + ], + [ + 83.3118164503403, + 271.60760156981326 + ], + [ + 83.008026747629017, + 272.00760301653474 + ], + [ + 82.700806760383514, + 272.42180331747943 + ], + [ + 82.403656957342847, + 272.82639345802357 + ], + [ + 82.1061843831784, + 273.23967297338015 + ], + [ + 81.808023653443627, + 273.64600182387522 + ], + [ + 81.5104180092249, + 274.04864610430377 + ], + [ + 81.208054561738308, + 274.46120107641559 + ], + [ + 80.90896700294752, + 274.86943239633939 + ], + [ + 80.6020177916498, + 275.27567019214507 + ], + [ + 80.29038146945355, + 275.68354436232391 + ], + [ + 79.977045500573482, + 276.08887099704054 + ], + [ + 79.66426420139075, + 276.48235303278938 + ], + [ + 79.34463353698176, + 276.881815965429 + ], + [ + 79.024840945698884, + 277.28303570138957 + ], + [ + 78.7114731992123, + 277.67582156899226 + ], + [ + 78.38657734282134, + 278.06996781368719 + ], + [ + 78.054696193955053, + 278.455980508159 + ], + [ + 77.7225593544591, + 278.83203646656739 + ], + [ + 77.38459271825252, + 279.21342056827211 + ], + [ + 77.043440885706772, + 279.58025878916771 + ], + [ + 76.691761850380317, + 279.94939441859515 + ], + [ + 76.334052967337669, + 280.30671260295452 + ], + [ + 75.97488195318148, + 280.66507728485772 + ], + [ + 75.629953681337113, + 281.03434940862763 + ], + [ + 75.289919146478113, + 281.40808300988755 + ], + [ + 74.957890512255744, + 281.78762083937164 + ], + [ + 74.61069312319708, + 282.14784940549623 + ], + [ + 74.268117475845457, + 282.51919980361157 + ], + [ + 73.939932942898864, + 282.897187071079 + ], + [ + 73.60902694379719, + 283.28127253962839 + ], + [ + 73.26187345335272, + 283.64558203243411 + ], + [ + 72.882206670055623, + 283.97929581073873 + ], + [ + 72.475616026106366, + 284.27558916339854 + ], + [ + 72.028332054748546, + 284.51127251024 + ], + [ + 71.561617860463073, + 284.70567680780539 + ], + [ + 71.076030508226424, + 284.85836767672782 + ], + [ + 70.57827746426554, + 284.97613054022446 + ], + [ + 70.079076995481444, + 285.05703327450783 + ], + [ + 69.5748837510616, + 285.09971374952835 + ], + [ + 69.063962702022351, + 285.12046083387355 + ], + [ + 68.563744432329983, + 285.11709995247287 + ], + [ + 68.060326424231974, + 285.09678769970003 + ], + [ + 67.554284642713256, + 285.06100522352665 + ], + [ + 67.054549750564675, + 285.0042460151065 + ], + [ + 66.545065346125511, + 284.92472156362015 + ], + [ + 66.043390549711788, + 284.83275535391442 + ], + [ + 65.549985428484476, + 284.73476004576622 + ], + [ + 65.046788114098888, + 284.631107537696 + ], + [ + 64.551830991923993, + 284.53074028541693 + ], + [ + 64.058137094154645, + 284.43759038969978 + ], + [ + 63.558672000005735, + 284.34451224422952 + ], + [ + 63.066188956770723, + 284.2504820688963 + ], + [ + 62.559855146076821, + 284.15824329375869 + ], + [ + 62.060300020338651, + 284.07676997046821 + ], + [ + 61.555375288956512, + 283.99015750996932 + ], + [ + 61.059573382844931, + 283.89771521558265 + ], + [ + 60.554170709383278, + 283.80155055981288 + ], + [ + 60.05475095602791, + 283.7092439597493 + ], + [ + 59.556108469295, + 283.63760707603552 + ], + [ + 59.050085256459049, + 283.57082888138285 + ], + [ + 58.554079221473096, + 283.50078759920848 + ], + [ + 58.049122037234191, + 283.43796908991379 + ], + [ + 57.548012931299667, + 283.37297135873149 + ], + [ + 57.041054473785486, + 283.30054201628576 + ], + [ + 56.535357338581214, + 283.23228071570924 + ], + [ + 56.025294265320561, + 283.16994237999893 + ], + [ + 55.516535219170464, + 283.1063120406447 + ], + [ + 55.010421113446377, + 283.04365698085604 + ], + [ + 54.50724132361163, + 282.98371303641807 + ], + [ + 54.007845854278571, + 282.9251364451053 + ], + [ + 53.510114858210443, + 282.8693954717275 + ], + [ + 53.000059119974544, + 282.81785410280639 + ], + [ + 52.501064743325657, + 282.7665685404038 + ], + [ + 51.996149680606521, + 282.71629824020334 + ], + [ + 51.492649614410453, + 282.67086507471117 + ], + [ + 50.993898460690666, + 282.62844600133946 + ], + [ + 50.4900056641631, + 282.58474739828745 + ], + [ + 49.981795346048173, + 282.53899522932784 + ], + [ + 49.481558364371104, + 282.494296787753 + ], + [ + 48.975924377169882, + 282.44815077690021 + ], + [ + 48.47576295771745, + 282.39764721154978 + ], + [ + 47.969365187492635, + 282.34305992247931 + ], + [ + 47.469135404285957, + 282.2909105002542 + ], + [ + 46.963367315854384, + 282.241339803428 + ], + [ + 46.460553195255677, + 282.18180465365015 + ], + [ + 45.962089619869424, + 282.1113606571779 + ], + [ + 45.464282740427514, + 282.03557828673394 + ], + [ + 44.965446840505372, + 281.95260170544867 + ], + [ + 44.48310392745308, + 281.80852907174392 + ], + [ + 44.03307077545179, + 281.64203183637829 + ], + [ + 43.571481088557206, + 281.45296508342767 + ], + [ + 44.000027803931573, + 281.7167437961748 + ], + [ + 43.512981795732543, + 281.82995514890206 + ], + [ + 43.025649361959218, + 281.70322506069357 + ], + [ + 42.547457434795724, + 281.54396651387651 + ], + [ + 42.063555921705813, + 281.40951714248621 + ], + [ + 41.558995382508158, + 281.36036543662351 + ], + [ + 41.050245896054847, + 281.33259579791752 + ], + [ + 40.552319859766627, + 281.28082003831094 + ], + [ + 40.046157955099488, + 281.2369708492219 + ], + [ + 39.534854102612591, + 281.21875871374516 + ], + [ + 39.028741606088857, + 281.22372600467969 + ], + [ + 38.527591843553715, + 281.22626633001181 + ], + [ + 38.018797964065008, + 281.20393715563188 + ], + [ + 37.505732715326232, + 281.17362751572216 + ], + [ + 37.00543487370377, + 281.1445014468153 + ], + [ + 36.494500739441996, + 281.10525133727231 + ], + [ + 35.987996267790479, + 281.07121576765076 + ], + [ + 35.485785037074038, + 281.03476550496828 + ], + [ + 34.986647288616929, + 280.99402970774713 + ], + [ + 34.47398414074344, + 280.95828584393922 + ], + [ + 33.969376044887284, + 280.9199702218487 + ], + [ + 33.45972230268471, + 280.86895002016144 + ], + [ + 32.958507763090864, + 280.82154033756717 + ], + [ + 32.44739493321817, + 280.77454535226968 + ], + [ + 31.934023306157695, + 280.72660586245144 + ], + [ + 31.426897598885549, + 280.68285996382031 + ], + [ + 30.928149209942049, + 280.63568777715881 + ], + [ + 30.414306545035686, + 280.58866292171331 + ], + [ + 29.908825245642547, + 280.5434660651336 + ], + [ + 29.397371795790821, + 280.50079139657652 + ], + [ + 28.888809935962673, + 280.47006831445907 + ], + [ + 28.376428467763979, + 280.45331563697158 + ], + [ + 27.860341482125307, + 280.43210990784911 + ], + [ + 27.354104759586345, + 280.40787958339558 + ], + [ + 26.83668674942297, + 280.39090850987503 + ], + [ + 26.324138530944904, + 280.38139727403177 + ], + [ + 25.816261672876802, + 280.35931592092254 + ], + [ + 25.303638193254713, + 280.33039373856934 + ], + [ + 24.788034819143629, + 280.29783527571755 + ], + [ + 24.288930747062427, + 280.25673956397645 + ], + [ + 23.790697135193636, + 280.209660320754 + ], + [ + 23.292329619723837, + 280.15826295381407 + ], + [ + 22.785684050684022, + 280.08558688739686 + ], + [ + 22.288675519057435, + 279.9740377922767 + ], + [ + 21.810568459594588, + 279.82556140318894 + ], + [ + 21.345846537259998, + 279.63692700054628 + ], + [ + 20.88465514913813, + 279.4130851808759 + ], + [ + 20.460930668391814, + 279.14548146751969 + ], + [ + 20.058443756957878, + 278.83329462403987 + ], + [ + 19.692450165869509, + 278.48472177639491 + ], + [ + 19.371711177638257, + 278.09675765544779 + ], + [ + 19.095002071800511, + 277.66399591860988 + ], + [ + 18.845172131152562, + 277.21786477706752 + ], + [ + 18.615552779693544, + 276.76634726201019 + ], + [ + 18.407812637245755, + 276.30055816196455 + ], + [ + 18.230236608123153, + 275.83118286988741 + ], + [ + 18.071970392550657, + 275.34431230035096 + ], + [ + 17.937818088995485, + 274.86182751796611 + ], + [ + 17.820726963189703, + 274.36930427570155 + ], + [ + 17.720358228356371, + 273.8688175406831 + ], + [ + 17.65067688805836, + 273.36979859405966 + ], + [ + 17.589501035797053, + 272.86814005734294 + ], + [ + 17.524448541897826, + 272.36244944863336 + ], + [ + 17.454028044253072, + 271.86134195563233 + ], + [ + 17.399563953154942, + 271.36232957422118 + ], + [ + 17.369343300096517, + 270.84929953003245 + ], + [ + 17.342531694409534, + 270.33664828369677 + ], + [ + 17.300787496991482, + 269.82401067775174 + ], + [ + 17.246896475605503, + 269.323646653166 + ], + [ + 17.190596588706665, + 268.82514498637738 + ], + [ + 17.128223655830141, + 268.32855882972115 + ], + [ + 17.053910076505232, + 267.82758071236515 + ], + [ + 16.97793797986823, + 267.33242104223348 + ], + [ + 16.909787792526206, + 266.83519731026621 + ], + [ + 16.830165607724865, + 266.33430748207235 + ], + [ + 16.738335777100051, + 265.82885646521345 + ], + [ + 16.648746469223514, + 265.33645186117229 + ], + [ + 16.553623062616332, + 264.84167300335361 + ], + [ + 16.449396181194128, + 264.34573798605106 + ], + [ + 16.335865332677297, + 263.85217841457808 + ], + [ + 16.210522944594235, + 263.36315649916662 + ], + [ + 16.084379723198843, + 262.87530735231212 + ], + [ + 15.95993040742767, + 262.37488769554943 + ], + [ + 15.833263726892213, + 261.88467482142283 + ], + [ + 15.691841652669339, + 261.40079057151559 + ], + [ + 15.552406115752442, + 260.90800155828 + ], + [ + 15.426309141235372, + 260.42384617068456 + ], + [ + 15.298895293899314, + 259.9397824476311 + ], + [ + 15.173340887641759, + 259.43906755117467 + ], + [ + 15.057978909572363, + 258.93811883702239 + ], + [ + 14.935815896031846, + 258.436824030104 + ], + [ + 14.80815109840635, + 257.94988269616783 + ], + [ + 14.687532457230141, + 257.45981683632135 + ], + [ + 14.571106304808803, + 256.96877779958947 + ], + [ + 14.446160950810642, + 256.47661320979216 + ], + [ + 14.312594856578274, + 255.98474054112651 + ], + [ + 14.179946540139463, + 255.49301055812944 + ], + [ + 14.041988708564876, + 254.99857685648126 + ], + [ + 13.900182786165136, + 254.5039571128583 + ], + [ + 13.76310427633913, + 254.01249369667607 + ], + [ + 13.628567735824182, + 253.52349975044882 + ], + [ + 13.479994874542781, + 253.03637967291797 + ], + [ + 13.324540827742192, + 252.55057144450288 + ], + [ + 13.170638537973705, + 252.06814714908481 + ], + [ + 13.007666081386821, + 251.59080521965871 + ], + [ + 12.83033254077308, + 251.11797261579312 + ], + [ + 12.649351025797438, + 250.64767959440849 + ], + [ + 12.47211835349593, + 250.17759110427343 + ], + [ + 12.295272583061722, + 249.70837146838235 + ], + [ + 12.122841555313475, + 249.23901349059682 + ], + [ + 11.953013683547034, + 248.75531205493945 + ], + [ + 11.775626790994069, + 248.27516596179052 + ], + [ + 11.583445395232277, + 247.80040156331131 + ], + [ + 11.396052418317956, + 247.32794630412604 + ], + [ + 11.219888514086593, + 246.85612357892219 + ], + [ + 11.043456043692371, + 246.38610275083903 + ], + [ + 10.864483466495214, + 245.91725150291592 + ], + [ + 10.683272480472732, + 245.43473784178994 + ], + [ + 10.505399701240911, + 244.95506485539522 + ], + [ + 10.329857927459646, + 244.47859992610452 + ], + [ + 10.162445086805773, + 244.0042076023781 + ], + [ + 10.010164951915643, + 243.52747395482018 + ], + [ + 9.8748089809401254, + 243.04574100519704 + ], + [ + 9.7430235966552328, + 242.54918332706492 + ], + [ + 9.6159081086981768, + 242.05301093447011 + ], + [ + 9.50036463886246, + 241.5635047279292 + ], + [ + 9.3922962987551557, + 241.06514090050072 + ], + [ + 9.2857295207188848, + 240.56230043125126 + ], + [ + 9.1902649891308688, + 240.0561382964508 + ], + [ + 9.10542868540135, + 239.56126111595148 + ], + [ + 9.0309438926767758, + 239.06378266738236 + ], + [ + 8.9638415508071549, + 238.56766502863232 + ], + [ + 8.8928320396380762, + 238.07174923523786 + ], + [ + 8.81735484428336, + 237.57595490469331 + ], + [ + 8.7377034205807576, + 237.08200821456791 + ], + [ + 8.64685247796824, + 236.58780863188488 + ], + [ + 8.5531291089265657, + 236.08060314933252 + ], + [ + 8.4620074950271924, + 235.57898205062989 + ], + [ + 8.3625857475058183, + 235.07777091283808 + ], + [ + 8.25219051892706, + 234.58947317239733 + ], + [ + 8.127085743840194, + 234.10172270075842 + ], + [ + 7.9930486022905409, + 233.61610867118736 + ], + [ + 7.8593168470142833, + 233.13271072485017 + ], + [ + 7.7255381890081978, + 232.63372258298742 + ], + [ + 7.5895307433353514, + 232.13670017433097 + ], + [ + 7.44350468254637, + 231.64357033047156 + ], + [ + 7.300978882483327, + 231.15185262104163 + ], + [ + 7.1671263252014157, + 230.66188803889037 + ], + [ + 7.038020669557894, + 230.17246656431027 + ], + [ + 6.9168029031352036, + 229.68093331581738 + ], + [ + 6.8097844168187693, + 229.18211463408261 + ], + [ + 6.7159771766018368, + 228.67838575264216 + ], + [ + 6.62698442724862, + 228.17241065621991 + ], + [ + 6.5423369647293468, + 227.67803777814214 + ], + [ + 6.4626858594639724, + 227.17201086195027 + ], + [ + 6.3907413601505327, + 226.67060679379955 + ], + [ + 6.3197313659925634, + 226.1593192218233 + ], + [ + 6.2495242043379662, + 225.65632560016911 + ], + [ + 6.1836219059287725, + 225.14542782222611 + ], + [ + 6.1269306011604812, + 224.64817636136237 + ], + [ + 6.0722942044591663, + 224.14734706002292 + ], + [ + 6.0182476438688131, + 223.64283879745176 + ], + [ + 5.9646965959146421, + 223.13450377923468 + ], + [ + 5.9089130261427192, + 222.62314094210262 + ], + [ + 5.8477848171307052, + 222.10929815818483 + ], + [ + 5.7840411650332042, + 221.6119080928998 + ], + [ + 5.7195823536269632, + 221.11229395808519 + ], + [ + 5.6557954343076133, + 220.60963742342838 + ], + [ + 5.59163500529945, + 220.10252564082541 + ], + [ + 5.530445925703364, + 219.59358092371372 + ], + [ + 5.4704653539504422, + 219.08351774564213 + ], + [ + 5.4071190842928836, + 218.57225950865421 + ], + [ + 5.3386929867853317, + 218.05888670283659 + ], + [ + 5.2712267465708864, + 217.54567609174657 + ], + [ + 5.2018516396394912, + 217.03104236109283 + ], + [ + 5.1245912165274223, + 216.51775085210014 + ], + [ + 5.0465775665155892, + 216.02275707420569 + ], + [ + 4.97306344440832, + 215.52472165453023 + ], + [ + 4.9065715480539058, + 215.02477143188125 + ], + [ + 4.8409377333275634, + 214.52339722019877 + ], + [ + 4.77389517573852, + 214.02181270704423 + ], + [ + 4.7080549699492176, + 213.51901604324738 + ], + [ + 4.6485365435467525, + 213.01619905436598 + ], + [ + 4.5927297623256509, + 212.51130211804821 + ], + [ + 4.5365705596351145, + 212.00560505721302 + ], + [ + 4.4768858523278876, + 211.50118345455758 + ], + [ + 4.4183887581846921, + 211.002713539241 + ], + [ + 4.3588992000269631, + 210.49018161263808 + ], + [ + 4.2984185132078618, + 209.98204419507735 + ], + [ + 4.2342709691744549, + 209.478117600731 + ], + [ + 4.1686738911080559, + 208.97906966562223 + ], + [ + 4.0987416543249946, + 208.46526632597903 + ], + [ + 4.0320030312372293, + 207.96662674398934 + ], + [ + 3.9623617662216142, + 207.46981020930588 + ], + [ + 3.8786442772220386, + 206.96366085504616 + ], + [ + 3.7934786771397517, + 206.46248574838472 + ], + [ + 3.7146600522361668, + 205.96400933580463 + ], + [ + 3.6303700520390474, + 205.47112562300796 + ], + [ + 3.5352608448874818, + 204.96674858727991 + ], + [ + 3.443295308735443, + 204.46962341362772 + ], + [ + 3.3522747360342962, + 203.977130919035 + ], + [ + 3.2535921725196628, + 203.47275830900242 + ], + [ + 3.1506720376538615, + 202.97710463720188 + ], + [ + 3.0466531299405908, + 202.47923658536095 + ], + [ + 2.9445046877376493, + 201.9800108700093 + ], + [ + 2.8395325667273967, + 201.47976039539316 + ], + [ + 2.7374839392910157, + 200.97762091515011 + ], + [ + 2.6401492109698932, + 200.47406928635743 + ], + [ + 2.5439519402051669, + 199.97322120719463 + ], + [ + 2.4561254494055409, + 199.47486543649762 + ], + [ + 2.3766262728177683, + 198.96598692779057 + ], + [ + 2.2950171200739748, + 198.46770518011661 + ], + [ + 2.2083755278575632, + 197.96885980768667 + ], + [ + 2.1167672594832836, + 197.46760520084058 + ], + [ + 2.0175536077874763, + 196.97220144474562 + ], + [ + 1.8941834163552163, + 196.48357707969072 + ], + [ + 1.7482170725591191, + 195.99990324964873 + ], + [ + 1.58592160901099, + 195.52167463453728 + ], + [ + 1.389793950541194, + 195.0539131839908 + ], + [ + 1.1651920761643619, + 194.60207050225117 + ], + [ + 0.8932832182219903, + 194.1740343389842 + ], + [ + 0.57696512561560054, + 193.77567871565879 + ], + [ + 0.21887245468423802, + 193.42411060602464 + ], + [ + -0.18423284127579198, + 193.11545342108977 + ], + [ + -0.60575796385971581, + 192.8411914161623 + ], + [ + -1.0478400801590335, + 192.60331177939128 + ], + [ + -1.510703476982028, + 192.39442577547595 + ], + [ + -1.9864512356398403, + 192.21498985050255 + ], + [ + -2.4669347887584445, + 192.07195224422017 + ], + [ + -2.9549842310898797, + 191.96027992349241 + ], + [ + -3.4606897598001995, + 191.8718717806818 + ], + [ + -3.9602255064914536, + 191.79544673792378 + ], + [ + -4.4686018742172058, + 191.72199343214339 + ], + [ + -4.9726089729809919, + 191.64498126885806 + ], + [ + -5.4734635673552985, + 191.56031610319241 + ], + [ + -5.9683478359973758, + 191.46270827247943 + ], + [ + -6.4695457051822975, + 191.36201221283795 + ], + [ + -6.963968342793188, + 191.27040005081176 + ], + [ + -7.4648400072378314, + 191.18411911122902 + ], + [ + -7.9623384547658427, + 191.08855319372751 + ], + [ + -8.4667743368248711, + 190.97614623702486 + ], + [ + -8.96689454267905, + 190.85690121710002 + ], + [ + -9.4557231007984015, + 190.74413841685339 + ], + [ + -9.94631416387003, + 190.63111110707436 + ], + [ + -10.43707494023503, + 190.50382307161459 + ], + [ + -10.930502178133626, + 190.35895012502255 + ], + [ + -11.41456071771391, + 190.20704877244796 + ], + [ + -11.891440480551204, + 190.03898356240933 + ], + [ + -12.366769046185819, + 189.85208489179118 + ], + [ + -12.82945206772585, + 189.65968970353009 + ], + [ + -13.298211668417256, + 189.45438926929896 + ], + [ + -13.755437828809491, + 189.23936811288746 + ], + [ + -14.210369108637506, + 189.01091771009521 + ], + [ + -14.651028938665681, + 188.76580193007328 + ], + [ + -15.084061613983216, + 188.495346395976 + ], + [ + -15.501878763799233, + 188.20120303205354 + ], + [ + -15.89864635119778, + 187.88574432466263 + ], + [ + -16.275049140369102, + 187.5522445131835 + ], + [ + -16.609504913834943, + 187.17102119337412 + ], + [ + -16.895663533617995, + 186.75949738879558 + ], + [ + -17.11716345801414, + 186.31109857590468 + ], + [ + -17.25762053606277, + 185.82056890243965 + ], + [ + -17.331375378359489, + 185.31909156078231 + ], + [ + -17.361087680433887, + 184.80937254261508 + ], + [ + -17.336836602727228, + 184.29814477568817 + ], + [ + -17.264690323178755, + 183.79015811961293 + ], + [ + -17.188774254993625, + 183.29366904260954 + ], + [ + -17.100000004880847, + 182.79521473445635 + ], + [ + -16.99857640332824, + 182.30427818619134 + ], + [ + -16.888778727267415, + 181.8106303247433 + ], + [ + -16.782581016621975, + 181.31457883120265 + ], + [ + -16.68531800770203, + 180.81431202502333 + ], + [ + -16.577630646267391, + 180.31580147573695 + ], + [ + -16.460473056964194, + 179.82015314374124 + ], + [ + -16.340956845149023, + 179.32362722438231 + ], + [ + -16.220229935032631, + 178.83374154397663 + ], + [ + -16.100515790119822, + 178.33333951680075 + ], + [ + -15.99941222843497, + 177.83948609546303 + ], + [ + -15.901058343242854, + 177.33294799605943 + ], + [ + -15.802460945473504, + 176.84161830897753 + ], + [ + -15.701329302038834, + 176.33938876637504 + ], + [ + -15.607786617590694, + 175.84163933972869 + ], + [ + -15.516459109733082, + 175.333240500427 + ], + [ + -15.432020626015467, + 174.83040935508072 + ], + [ + -15.361288141223263, + 174.33375582228609 + ], + [ + -15.292679954367388, + 173.83054929586976 + ], + [ + -15.216812926754098, + 173.32040517527889 + ], + [ + -15.14600463382749, + 172.82203806248634 + ], + [ + -15.078534065104998, + 172.315104649416 + ], + [ + -15.012892022693421, + 171.80309750986012 + ], + [ + -14.945195276019812, + 171.28808283162573 + ], + [ + -14.884791275911924, + 170.78075177503607 + ], + [ + -14.828933777415042, + 170.27833726607477 + ], + [ + -14.777184556327851, + 169.76129221390934 + ], + [ + -14.735173997940871, + 169.24552748681549 + ], + [ + -14.688644695850579, + 168.73184667490114 + ], + [ + -14.634325021230703, + 168.22269430987208 + ], + [ + -14.581397860153496, + 167.71926929903708 + ], + [ + -14.533609030375455, + 167.20287998369167 + ], + [ + -14.486621733324185, + 166.68889298311686 + ], + [ + -14.437169555344388, + 166.17992846313317 + ], + [ + -14.380293779704054, + 165.67667315206177 + ], + [ + -14.31777512447546, + 165.17887944186634 + ], + [ + -14.242352602321505, + 164.66754165215858 + ], + [ + -14.159468827603515, + 164.1644354912934 + ], + [ + -14.076859407427, + 163.65659750383313 + ], + [ + -13.997540441738172, + 163.15165507122933 + ], + [ + -13.92302402567147, + 162.65271795246761 + ], + [ + -13.847895862839216, + 162.15340248223359 + ], + [ + -13.761841599731579, + 161.66042291257742 + ], + [ + -13.658804774574964, + 161.16141173312627 + ], + [ + -13.544272985850135, + 160.66936132345063 + ], + [ + -13.422669651752953, + 160.16920923857796 + ], + [ + -13.293100178100346, + 159.67305809101595 + ], + [ + -13.146491055731163, + 159.18537063020813 + ], + [ + -12.975644986248964, + 158.70357812727755 + ], + [ + -12.79559745015346, + 158.23403295989823 + ], + [ + -12.602518456729991, + 157.76800078881612 + ], + [ + -12.398270673931059, + 157.30250458145918 + ], + [ + -12.1889169591196, + 156.83366156360788 + ], + [ + -11.98326306501871, + 156.377424124643 + ], + [ + -11.777880688815909, + 155.91723146964318 + ], + [ + -11.574466564708736, + 155.45132154877945 + ], + [ + -11.366426738911308, + 154.98014708584628 + ], + [ + -11.161702590903836, + 154.52312319132969 + ], + [ + -10.957412760534117, + 154.06482019744135 + ], + [ + -10.751483862131815, + 153.60300622017536 + ], + [ + -10.540392662001029, + 153.1429232348423 + ], + [ + -10.325511656365741, + 152.68722526039451 + ], + [ + -10.109985027400029, + 152.22888912203791 + ], + [ + -9.89833089496425, + 151.76690317700442 + ], + [ + -9.6895524588333348, + 151.29924166994366 + ], + [ + -9.4896822936380847, + 150.82630031812246 + ], + [ + -9.29412034399728, + 150.34661115416193 + ], + [ + -9.0979596718810161, + 149.86644270088581 + ], + [ + -8.89904844545215, + 149.38843100260377 + ], + [ + -8.7102062073991124, + 148.92386064964779 + ], + [ + -8.5305420227703976, + 148.45421555482707 + ], + [ + -8.3501280835355214, + 147.98792211927213 + ], + [ + -8.1591754031054577, + 147.50678352807455 + ], + [ + -7.9763650282645084, + 147.02439623621604 + ], + [ + -7.7980865475902554, + 146.54410524577227 + ], + [ + -7.6176126658998653, + 146.06752967987913 + ], + [ + -7.440962607875532, + 145.59530325802439 + ], + [ + -7.2807726427790129, + 145.12167007275721 + ], + [ + -7.1242986536044528, + 144.62884387842283 + ], + [ + -6.9758759870235689, + 144.13871648898908 + ], + [ + -6.8382053309290471, + 143.64865005459973 + ], + [ + -6.7080900967431472, + 143.15808097782514 + ], + [ + -6.586746383875461, + 142.67229432077059 + ], + [ + -6.4721900541451385, + 142.17273082973719 + ], + [ + -6.369632113000737, + 141.67643307946588 + ], + [ + -6.2857691050622266, + 141.17816152131596 + ], + [ + -6.2209931340811355, + 140.67649325502177 + ], + [ + -6.1653038253496515, + 140.16252019044856 + ], + [ + -6.1187915504433308, + 139.65630831995534 + ], + [ + -6.095077392726326, + 139.15254485022564 + ], + [ + -6.10278129220409, + 138.65079569793093 + ], + [ + -6.1178105150069095, + 138.13774698820933 + ], + [ + -6.1337018701467469, + 137.63039283711666 + ], + [ + -6.1644352988472857, + 137.12880152742125 + ], + [ + -6.2111247818772943, + 136.61679789197663 + ], + [ + -6.2632906516500046, + 136.11255610304093 + ], + [ + -6.3152156290181569, + 135.61466145009007 + ], + [ + -6.3816635817487866, + 135.10772462519691 + ], + [ + -6.4706203235077293, + 134.61135214293995 + ], + [ + -6.5763289541823928, + 134.11255133847834 + ], + [ + -6.6987687567778362, + 133.6224483484263 + ], + [ + -6.8470448739302787, + 133.13075177927249 + ], + [ + -7.0121062639209981, + 132.6558043697658 + ], + [ + -7.2081913737068994, + 132.19004913967305 + ], + [ + -7.4468505807907475, + 131.74062121639028 + ], + [ + -7.7029455094826549, + 131.29894751008212 + ], + [ + -7.9674750621854162, + 130.87373083729634 + ], + [ + -8.2699773134199077, + 130.461345773444 + ], + [ + -8.5969176953248727, + 130.06536233526416 + ], + [ + -8.93801839406152, + 129.69161535304667 + ], + [ + -9.305090263745095, + 129.34520991370303 + ], + [ + -9.6867125831852974, + 129.01247744604666 + ], + [ + -10.081199849776402, + 128.68294796442822 + ], + [ + -10.486522059709859, + 128.37861548214556 + ], + [ + -10.904542193808862, + 128.08859241718994 + ], + [ + -11.315402848929027, + 127.79949754136526 + ], + [ + -11.730230630005956, + 127.51101431451133 + ], + [ + -12.142706600720828, + 127.22648939703615 + ], + [ + -12.55835477185776, + 126.93416087867138 + ], + [ + -12.986384120505297, + 126.64746552120236 + ], + [ + -13.41889253153323, + 126.37173948937506 + ], + [ + -13.850204744984902, + 126.10437260476198 + ], + [ + -14.283121591108451, + 125.84780356627182 + ], + [ + -14.7237341625597, + 125.58836834644598 + ], + [ + -15.162011619929633, + 125.33958889683137 + ], + [ + -15.613237903254582, + 125.10180118353814 + ], + [ + -16.067135923889349, + 124.88818559928201 + ], + [ + -16.533252978373522, + 124.69505259448961 + ], + [ + -17.008471080928103, + 124.52415490328137 + ], + [ + -17.501667272190254, + 124.38626472700891 + ], + [ + -17.992725843501262, + 124.28568358393741 + ], + [ + -18.49912542912238, + 124.22091890937048 + ], + [ + -19.007766175227783, + 124.198072787159 + ], + [ + -19.508293529619738, + 124.21204966386162 + ], + [ + -20.009830361394098, + 124.27282375569546 + ], + [ + -20.501339863268452, + 124.37293987314797 + ], + [ + -20.994326461558185, + 124.48049676782964 + ], + [ + -21.489184007994286, + 124.60989301115191 + ], + [ + -21.976327016273025, + 124.73901584894556 + ], + [ + -22.466544955461906, + 124.86831340414274 + ], + [ + -22.962773677927387, + 124.94227537986106 + ], + [ + -23.469136065855565, + 124.95117177772168 + ], + [ + -23.976844585718737, + 124.91302729020485 + ], + [ + -24.468908454178315, + 124.82155727954859 + ], + [ + -24.933193594256831, + 124.61602799045781 + ], + [ + -25.341156603632353, + 124.32656598825859 + ], + [ + -25.698973565813013, + 123.97619646246523 + ], + [ + -25.960334172496129, + 123.5416592625982 + ], + [ + -26.172047672351379, + 123.08274021768872 + ], + [ + -26.3439742381886, + 122.61243771713561 + ], + [ + -26.478272967462544, + 122.12908304069919 + ], + [ + -26.521688003881685, + 121.62989077655674 + ], + [ + -26.49389747834498, + 121.12355705236772 + ], + [ + -26.393457278515733, + 120.62391535411376 + ], + [ + -26.264543797669837, + 120.1343888332332 + ], + [ + -26.108843797262779, + 119.6519471504031 + ], + [ + -25.910821650025614, + 119.18412771897634 + ], + [ + -25.690490578921935, + 118.72237322394003 + ], + [ + -25.470361732078281, + 118.26130214960728 + ], + [ + -25.248379394730883, + 117.8050312824125 + ], + [ + -25.012923294280764, + 117.36005857426056 + ], + [ + -24.774114812146841, + 116.90453526537236 + ], + [ + -24.539775849485455, + 116.451528600684 + ], + [ + -24.313895793778503, + 115.99249991708788 + ], + [ + -24.099110062044897, + 115.53137680010427 + ], + [ + -23.882704714121829, + 115.0717271537988 + ], + [ + -23.667467292867148, + 114.61122637196839 + ], + [ + -23.460035862404457, + 114.15462271673775 + ], + [ + -23.244437698539851, + 113.6917637306906 + ], + [ + -23.024385668278928, + 113.23636186677054 + ], + [ + -22.808673147151627, + 112.77164728054309 + ], + [ + -22.60621098007638, + 112.30874087583548 + ], + [ + -22.412030962846742, + 111.84543969466934 + ], + [ + -22.222042969093678, + 111.36704070363199 + ], + [ + -22.030281028147751, + 110.89754470087578 + ], + [ + -21.820650145068569, + 110.42785398357071 + ], + [ + -21.613133616403363, + 109.96272085161081 + ], + [ + -21.41671492641758, + 109.49676889058311 + ], + [ + -21.232830609188024, + 109.03160856443984 + ], + [ + -21.050964828130592, + 108.55567384093958 + ], + [ + -20.876339114585225, + 108.08325684062916 + ], + [ + -20.687643805276757, + 107.60841655993448 + ], + [ + -20.49562519249319, + 107.14298180685697 + ], + [ + -20.298521249190237, + 106.67061663728474 + ], + [ + -20.101110749469839, + 106.20909646266192 + ], + [ + -19.908496375867585, + 105.73810778520705 + ], + [ + -19.725954759612687, + 105.26354227465194 + ], + [ + -19.5447355350028, + 104.79706452688269 + ], + [ + -19.34638355526803, + 104.33008805073709 + ], + [ + -19.138214568782232, + 103.87250174440965 + ], + [ + -18.914619115121532, + 103.41693208876117 + ], + [ + -18.653422380101777, + 102.9907544633526 + ], + [ + -18.371681167553589, + 102.58147369486707 + ], + [ + -18.039442473095168, + 102.20350717817496 + ], + [ + -17.699604015227418, + 101.85837979730924 + ], + [ + -17.456858927400379, + 101.42173540976073 + ], + [ + -17.113489082233432, + 101.06040711910006 + ], + [ + -17.216825056401095, + 100.57083157498677 + ], + [ + -16.985839062770385, + 100.12271043792495 + ], + [ + -16.72676622297114, + 99.6895837853887 + ], + [ + -16.473496064055571, + 99.253842668384777 + ], + [ + -16.247229085775992, + 98.80044278473828 + ], + [ + -16.040795876106987, + 98.340781789232011 + ], + [ + -15.861866082286781, + 97.866539062404215 + ], + [ + -15.736304389350527, + 97.378122877745653 + ], + [ + -15.650531353383265, + 96.8742640966797 + ], + [ + -15.558415145639371, + 96.376768776742878 + ], + [ + -15.475293622949504, + 95.875748738287456 + ], + [ + -15.401976463741631, + 95.3780817157853 + ], + [ + -15.332780349495529, + 94.8755898493973 + ], + [ + -15.248226087096636, + 94.369392489838944 + ], + [ + -15.143798295115316, + 93.879975676904877 + ], + [ + -15.033531605638418, + 93.378501221802154 + ], + [ + -14.921839530885784, + 92.878913068327961 + ], + [ + -14.797574151483568, + 92.385613308799549 + ], + [ + -14.667041840053786, + 91.900355227795757 + ], + [ + -14.529125179965496, + 91.404740350553226 + ], + [ + -14.386966314668136, + 90.91634951034321 + ], + [ + -14.244448172174939, + 90.4354378842495 + ], + [ + -14.097159129103469, + 89.947133992499957 + ], + [ + -13.945706429744204, + 89.451706148624012 + ], + [ + -13.792592715794505, + 88.973604865172788 + ], + [ + -13.623614423625831, + 88.491661923014433 + ], + [ + -13.452294451179364, + 88.019822490728814 + ], + [ + -13.279209126834935, + 87.545418618327574 + ], + [ + -13.097401810401456, + 87.0770872875117 + ], + [ + -12.902676007200103, + 86.609251869792217 + ], + [ + -12.70043113710458, + 86.1375489656086 + ], + [ + -12.505026400945651, + 85.668326079152465 + ], + [ + -12.313728404924373, + 85.201868617820182 + ], + [ + -12.116501840362819, + 84.731630024305957 + ], + [ + -11.912913486455061, + 84.256562647344552 + ], + [ + -11.714175687990958, + 83.782564731034029 + ], + [ + -11.518749118272163, + 83.314827671837733 + ], + [ + -11.319103310781683, + 82.849948511349808 + ], + [ + -11.11384196098385, + 82.37860356400914 + ], + [ + -10.914932688293368, + 81.913234848501517 + ], + [ + -10.712544157669816, + 81.451843247060012 + ], + [ + -10.500703020898166, + 80.980614828352444 + ], + [ + -10.293982410832024, + 80.513909482527112 + ], + [ + -10.089691869666783, + 80.0505715004734 + ], + [ + -9.8787461513773565, + 79.578490778412146 + ], + [ + -9.668852700527653, + 79.10838427165902 + ], + [ + -9.4613248839769835, + 78.642270963639447 + ], + [ + -9.2527179015160339, + 78.177707267297023 + ], + [ + -9.0424848938892346, + 77.718934121675517 + ], + [ + -8.8311345340274379, + 77.253377281540239 + ], + [ + -8.6260566693111542, + 76.793402153135787 + ], + [ + -8.4213424435046829, + 76.325330679425349 + ], + [ + -8.2225636159197, + 75.8551656151475 + ], + [ + -8.0337612892370576, + 75.391336907684334 + ], + [ + -7.8464976055039308, + 74.915203278989978 + ], + [ + -7.6829356268941646, + 74.4367607575801 + ], + [ + -7.5439522245495505, + 73.953724012746051 + ], + [ + -7.4159171446986347, + 73.465658294515393 + ], + [ + -7.3079505567938963, + 72.965704554231067 + ], + [ + -7.2104165481357976, + 72.469801109886049 + ], + [ + -7.0839361779520109, + 71.977959540137533 + ], + [ + -6.9303777417384342, + 71.493173466124347 + ], + [ + -6.7436669962609033, + 71.020868614665076 + ], + [ + -6.5228791613526207, + 70.56476756277867 + ], + [ + -6.2563766286298081, + 70.13023332463311 + ], + [ + -5.9562720472622512, + 69.726460974681814 + ], + [ + -5.61545989896896, + 69.355876107807234 + ], + [ + -5.2488184547341348, + 69.0135164810178 + ], + [ + -4.8544143005369529, + 68.697454441580618 + ], + [ + -4.4264309755668618, + 68.413588562235887 + ], + [ + -3.9896293749023428, + 68.149581864555529 + ], + [ + -3.543059119230469, + 67.8947861063702 + ], + [ + -3.0898143550449988, + 67.654683630231716 + ], + [ + -2.6303767682037105, + 67.442066303958939 + ], + [ + -2.1654001594198737, + 67.2456276554355 + ], + [ + -1.6897627144851497, + 67.062365705320914 + ], + [ + -1.2022065667688349, + 66.907079632989991 + ], + [ + -0.71832641996774194, + 66.771011385655328 + ], + [ + -0.23727228098319386, + 66.630766661082248 + ], + [ + 0.25435816882741041, + 66.485346157417027 + ], + [ + 0.74441776167267182, + 66.344458760123175 + ], + [ + 1.2287736996882455, + 66.213541058619427 + ], + [ + 1.7216702142384339, + 66.088690332056672 + ], + [ + 2.2206053705636934, + 65.965870044009137 + ], + [ + 2.707087643923622, + 65.847046268839492 + ], + [ + 3.1976375549465872, + 65.729710952361984 + ], + [ + 3.6912150714404346, + 65.610017849716129 + ], + [ + 4.188286771206486, + 65.484102764096576 + ], + [ + 4.6878523028818293, + 65.3526690319 + ], + [ + 5.1723202802809167, + 65.226938524309034 + ], + [ + 5.6572963878258395, + 65.104740718990172 + ], + [ + 6.1440673690859331, + 64.982162303731272 + ], + [ + 6.6291987394327743, + 64.854693317354389 + ], + [ + 7.1244943110641774, + 64.7211796215199 + ], + [ + 7.61303754486672, + 64.5911223923658 + ], + [ + 8.0995554694124987, + 64.464759136660547 + ], + [ + 8.5998966896037423, + 64.335426501289035 + ], + [ + 9.0952235712311218, + 64.209299526139617 + ], + [ + 9.5848494999004732, + 64.0820251643124 + ], + [ + 10.069982217819478, + 63.948954210272049 + ], + [ + 10.567236599254235, + 63.809557267521569 + ], + [ + 11.057078237704683, + 63.6671819193983 + ], + [ + 11.543261757252488, + 63.529686633553489 + ], + [ + 12.028024256160814, + 63.403353433738161 + ], + [ + 12.524961325432455, + 63.278460817299404 + ], + [ + 13.016338156960432, + 63.154126215517024 + ], + [ + 13.503577053265648, + 63.034538528072225 + ], + [ + 14.002767994120891, + 62.921347828280744 + ], + [ + 14.495497504777536, + 62.813612218621032 + ], + [ + 14.985609659376818, + 62.704325028182666 + ], + [ + 15.48265473449792, + 62.589120747376469 + ], + [ + 15.974234837355875, + 62.471275210235731 + ], + [ + 16.47043523311644, + 62.354475269367782 + ], + [ + 16.968388821074537, + 62.252657846152061 + ], + [ + 17.471053807003045, + 62.166634271614477 + ], + [ + 17.9695224084254, + 62.07282337100748 + ], + [ + 18.462403664974616, + 61.9698835996148 + ], + [ + 18.949330413548832, + 61.844705932520149 + ], + [ + 19.426353184452179, + 61.681355201496977 + ] + ], + "Outside": [ + [ + 19.389855122897487, + 56.168418396158664 + ], + [ + 19.650949367670556, + 55.742476952058709 + ], + [ + 19.157506563436623, + 55.826300550768195 + ], + [ + 19.435762135922822, + 55.415845307786611 + ], + [ + 19.905922114942634, + 55.239106870266582 + ], + [ + 20.370954600769856, + 55.0466841944834 + ], + [ + 20.81269170168407, + 54.811518513773812 + ], + [ + 21.296720446823411, + 54.657706786748385 + ], + [ + 21.777157194846946, + 54.502697218406119 + ], + [ + 22.251581461287437, + 54.3434123058805 + ], + [ + 22.728380615787486, + 54.166896964588162 + ], + [ + 23.202728758465632, + 53.988599161286061 + ], + [ + 23.683805266894524, + 53.826954199179674 + ], + [ + 24.166465068868678, + 53.66101209972436 + ], + [ + 24.644408600469365, + 53.494909104527537 + ], + [ + 25.121339062546269, + 53.310380842441411 + ], + [ + 25.595439935577524, + 53.1133015453387 + ], + [ + 26.072089538102116, + 52.924086365388 + ], + [ + 26.547367809932719, + 52.7385685820705 + ], + [ + 27.021063363575632, + 52.552056264781967 + ], + [ + 27.489537229856325, + 52.365307578096392 + ], + [ + 27.958816422942135, + 52.178321434658983 + ], + [ + 28.431498830215741, + 51.983791936816793 + ], + [ + 28.906330596129997, + 51.778140367087858 + ], + [ + 29.366725635595568, + 51.576889177577151 + ], + [ + 29.840702729597474, + 51.375705274464927 + ], + [ + 30.303751338242968, + 51.181392846397948 + ], + [ + 30.775412100609127, + 50.983934709961936 + ], + [ + 31.239120137336265, + 50.792310248425729 + ], + [ + 31.707391648353752, + 50.587560375656018 + ], + [ + 32.16472400231784, + 50.37911258280473 + ], + [ + 32.627957752240661, + 50.165858412185678 + ], + [ + 33.0876139799825, + 49.948386461200414 + ], + [ + 33.538518406498454, + 49.729687172248276 + ], + [ + 34.000235713032566, + 49.508712267127834 + ], + [ + 34.456484567715179, + 49.278786933746858 + ], + [ + 34.907775466865267, + 49.037030109751718 + ], + [ + 35.351518492976346, + 48.791903080190487 + ], + [ + 35.786497752555952, + 48.541250677642338 + ], + [ + 36.229515268093095, + 48.269967134079728 + ], + [ + 36.670591501354679, + 48.000531202234384 + ], + [ + 37.109159555823716, + 47.741842188960433 + ], + [ + 37.539613989276852, + 47.477964855991431 + ], + [ + 37.968501408809438, + 47.213128937692737 + ], + [ + 38.408591792732551, + 46.942401381341547 + ], + [ + 38.837634651684816, + 46.665723796447367 + ], + [ + 39.263131443272719, + 46.386652511009721 + ], + [ + 39.682887052722556, + 46.108985588171713 + ], + [ + 40.109931309911254, + 45.817496405923634 + ], + [ + 40.534029635334342, + 45.530314681686093 + ], + [ + 40.965369672019293, + 45.261709219385722 + ], + [ + 41.401489058829171, + 45.0111334832215 + ], + [ + 41.857820910348757, + 44.770607375687568 + ], + [ + 42.315666782080115, + 44.542606846247942 + ], + [ + 42.763788282981338, + 44.312910692793558 + ], + [ + 43.223596762056495, + 44.082015088003494 + ], + [ + 43.685637880333054, + 43.861288080829091 + ], + [ + 44.150291574557926, + 43.652219460616664 + ], + [ + 44.617758811388519, + 43.465490225721787 + ], + [ + 45.103187299388132, + 43.296572736009757 + ], + [ + 45.589482620268704, + 43.144946230434684 + ], + [ + 46.0793896521142, + 43.010151116889332 + ], + [ + 46.567215185139283, + 42.885252333533593 + ], + [ + 47.067587319329448, + 42.773056396757667 + ], + [ + 47.566028339639445, + 42.68987931768725 + ], + [ + 48.063645602306366, + 42.63921706540232 + ], + [ + 48.572106743140466, + 42.62305251370271 + ], + [ + 49.086058955769879, + 42.648052105826054 + ], + [ + 49.587979746563413, + 42.7189364820567 + ], + [ + 50.081315386828315, + 42.821944930958395 + ], + [ + 50.570689846630849, + 42.942858933539263 + ], + [ + 51.054629523302125, + 43.088351987230332 + ], + [ + 51.526154300127828, + 43.281792549702033 + ], + [ + 51.98572027297066, + 43.487333224849479 + ], + [ + 52.456484811598408, + 43.697943706528726 + ], + [ + 52.911838642144204, + 43.914447985659812 + ], + [ + 53.372756442104631, + 44.129273263407931 + ], + [ + 53.827673278318578, + 44.355076082275524 + ], + [ + 54.280779242261943, + 44.582783865004338 + ], + [ + 54.737147512641883, + 44.807730874920132 + ], + [ + 55.183254608150236, + 45.047127946139177 + ], + [ + 55.630670892855321, + 45.294101212980749 + ], + [ + 56.084031434035161, + 45.532158656615771 + ], + [ + 56.531678584228274, + 45.766313577555792 + ], + [ + 56.98364468052258, + 45.99667060424067 + ], + [ + 57.439330585243766, + 46.227852832513555 + ], + [ + 57.891759529422821, + 46.472030520146596 + ], + [ + 58.340989340307893, + 46.724971067090486 + ], + [ + 58.779508265209557, + 46.967643249298838 + ], + [ + 59.221614548781915, + 47.2109615508108 + ], + [ + 59.668214311414062, + 47.453941653661118 + ], + [ + 60.114584403795114, + 47.699595791227054 + ], + [ + 60.561060853983093, + 47.949863618540164 + ], + [ + 61.009249493676194, + 48.2011654577675 + ], + [ + 61.460123232367323, + 48.4550789184372 + ], + [ + 61.895823321703254, + 48.704134116151756 + ], + [ + 62.34223990964248, + 48.962585542838049 + ], + [ + 62.780713379578621, + 49.219848714499975 + ], + [ + 63.21518638614549, + 49.478434259942404 + ], + [ + 63.650615114106742, + 49.742947659055567 + ], + [ + 64.085498318455933, + 50.013035259770895 + ], + [ + 64.518072639378559, + 50.287126730166364 + ], + [ + 64.945613292594246, + 50.565785709766132 + ], + [ + 65.370386268225147, + 50.847524372309159 + ], + [ + 65.797484225534532, + 51.128805882490582 + ], + [ + 66.223833932080566, + 51.411916993023134 + ], + [ + 66.647468880997124, + 51.699355792621304 + ], + [ + 67.07009553899087, + 51.988544403379031 + ], + [ + 67.488014778840054, + 52.283835460859265 + ], + [ + 67.902621628438609, + 52.5871796527764 + ], + [ + 68.314959172097389, + 52.889106988428708 + ], + [ + 68.727238344951047, + 53.188590381173633 + ], + [ + 69.135518566725963, + 53.490309816746844 + ], + [ + 69.543106047377108, + 53.792570850865673 + ], + [ + 69.952819975493568, + 54.094488372508621 + ], + [ + 70.361836992248882, + 54.394530355796768 + ], + [ + 70.7733977794433, + 54.6893779541601 + ], + [ + 71.187976131347924, + 54.976712650203133 + ], + [ + 71.603310939241155, + 55.260999998872443 + ], + [ + 72.0156252773882, + 55.546506449335951 + ], + [ + 72.4377652826843, + 55.84209642611777 + ], + [ + 72.859673614114527, + 56.131358300488017 + ], + [ + 73.284525519161008, + 56.40956077951919 + ], + [ + 73.7150477360809, + 56.676706230215579 + ], + [ + 74.155625666875153, + 56.939839232351744 + ], + [ + 74.590561196382723, + 57.188531024342893 + ], + [ + 75.031922708085773, + 57.427280784914572 + ], + [ + 75.480201910178579, + 57.655946756781212 + ], + [ + 75.934392505711543, + 57.879221630364462 + ], + [ + 76.3925075558882, + 58.092759610506711 + ], + [ + 76.854082584409284, + 58.29574510168262 + ], + [ + 77.317808883277621, + 58.49208563718517 + ], + [ + 77.788269365432186, + 58.680610759914508 + ], + [ + 78.262483620111823, + 58.8611995971774 + ], + [ + 78.739335038873335, + 59.033213224775125 + ], + [ + 79.21978216311534, + 59.196791322698537 + ], + [ + 79.70582418004372, + 59.351488968301958 + ], + [ + 80.195586710039649, + 59.497594972814724 + ], + [ + 80.68623005090123, + 59.636820006816023 + ], + [ + 81.177395804253848, + 59.7737718647173 + ], + [ + 81.668803342724274, + 59.909176479985462 + ], + [ + 82.160498751721491, + 60.042060304805396 + ], + [ + 82.652204570744615, + 60.173405901527275 + ], + [ + 83.142582894080292, + 60.303170335249796 + ], + [ + 83.630554410936483, + 60.439192374331434 + ], + [ + 84.1179738094862, + 60.583275562202552 + ], + [ + 84.602050458934016, + 60.73302872248945 + ], + [ + 85.082026303920074, + 60.89011336785353 + ], + [ + 85.558715073836026, + 61.047876989331932 + ], + [ + 86.034136045114934, + 61.205744772063895 + ], + [ + 86.5070138725028, + 61.372784360553133 + ], + [ + 86.975077653869377, + 61.552141193548735 + ], + [ + 87.4523265045435, + 61.742408230819251 + ], + [ + 87.924254457435069, + 61.93432682490679 + ], + [ + 88.3924626973231, + 62.130708813955323 + ], + [ + 88.853781609723512, + 62.331547033233939 + ], + [ + 89.32047449086825, + 62.547470500532583 + ], + [ + 89.780226678386924, + 62.766468931410508 + ], + [ + 90.233080183806777, + 62.992103658346068 + ], + [ + 90.677986897703548, + 63.221351834574428 + ], + [ + 91.132340280572819, + 63.459586794518458 + ], + [ + 91.578516106062182, + 63.701490421866538 + ], + [ + 92.018589639129161, + 63.941588929310896 + ], + [ + 92.472557424401245, + 64.182927966116125 + ], + [ + 92.924336626759455, + 64.419997565886675 + ], + [ + 93.3735651415369, + 64.650923025506785 + ], + [ + 93.819398046363432, + 64.877942090376152 + ], + [ + 94.276318059927149, + 65.110949010627536 + ], + [ + 94.725523538095658, + 65.339637772969752 + ], + [ + 95.184986129820658, + 65.568819502330953 + ], + [ + 95.642107138996082, + 65.794447739584143 + ], + [ + 96.092824364673646, + 66.015453424769817 + ], + [ + 96.548898356771474, + 66.242517131212836 + ], + [ + 97.006567839001661, + 66.473669131632334 + ], + [ + 97.455719239401944, + 66.7089706361795 + ], + [ + 97.899283068926891, + 66.952535000163 + ], + [ + 98.330759987484441, + 67.211177098120956 + ], + [ + 98.725305744529024, + 67.5288472652761 + ], + [ + 99.072035528454535, + 67.898619766597022 + ], + [ + 99.377506333501657, + 68.295848450378 + ], + [ + 99.652817373650336, + 68.725833787315182 + ], + [ + 99.859124734077028, + 69.19374756437891 + ], + [ + 100.01104746005031, + 69.672295697709558 + ], + [ + 100.09694844780779, + 70.166095561445943 + ], + [ + 100.14477621273612, + 70.670386727403951 + ], + [ + 100.16007862382477, + 71.1703407109711 + ], + [ + 100.14575715079317, + 71.6789694133886 + ], + [ + 100.09450692724866, + 72.189055633644 + ], + [ + 100.02418874702229, + 72.690038061753725 + ], + [ + 99.919966651592233, + 73.188383262187159 + ], + [ + 99.773461215415608, + 73.680761059519739 + ], + [ + 99.613354368996141, + 74.163131110143027 + ], + [ + 99.4430760381331, + 74.6347017577766 + ], + [ + 99.262699658625365, + 75.111626488398727 + ], + [ + 99.092150162773436, + 75.597423480577945 + ], + [ + 98.925985088045024, + 76.075261857693121 + ], + [ + 98.751489939695645, + 76.545686043163457 + ], + [ + 98.562107886946663, + 77.020759085050116 + ], + [ + 98.3777797175229, + 77.487666892204246 + ], + [ + 98.190735070709351, + 77.9607026482526 + ], + [ + 97.9913795858837, + 78.436602981549143 + ], + [ + 97.780924161547389, + 78.908426438623309 + ], + [ + 97.567663482905019, + 79.379298498515425 + ], + [ + 97.36033524250837, + 79.8377934003357 + ], + [ + 97.153731750182644, + 80.302429390573508 + ], + [ + 96.9489173809901, + 80.770927311160108 + ], + [ + 96.747827830116734, + 81.2433257331134 + ], + [ + 96.55133773416, + 81.719936932185746 + ], + [ + 96.359704340393876, + 82.18361757530451 + ], + [ + 96.160708583808926, + 82.649195912697039 + ], + [ + 95.954986121949, + 83.1147754553854 + ], + [ + 95.745259510249824, + 83.58054861716478 + ], + [ + 95.52837705495196, + 84.043571593768235 + ], + [ + 95.303753354202357, + 84.504125195991264 + ], + [ + 95.078099807761674, + 84.964248396049555 + ], + [ + 94.852585499875346, + 85.427051847433589 + ], + [ + 94.622369820572516, + 85.888536713182 + ], + [ + 94.3864669951422, + 86.350052706742531 + ], + [ + 94.156946255928091, + 86.79494496897955 + ], + [ + 93.9243126252333, + 87.23874823018383 + ], + [ + 93.684289284880663, + 87.68045430846179 + ], + [ + 93.438173323357432, + 88.120691325799328 + ], + [ + 93.184031135469979, + 88.557390768015807 + ], + [ + 92.9257725468792, + 88.991918560812024 + ], + [ + 92.6620650402133, + 89.423204613322156 + ], + [ + 92.395091784284631, + 89.8529650280623 + ], + [ + 92.122700933230121, + 90.282097728079762 + ], + [ + 91.846228860684093, + 90.710431529062276 + ], + [ + 91.56245613455404, + 91.135060555447723 + ], + [ + 91.272310671995328, + 91.557177648399616 + ], + [ + 90.974775619169478, + 91.974762403380865 + ], + [ + 90.672888682337089, + 92.389526705622274 + ], + [ + 90.365755628133229, + 92.801332496525987 + ], + [ + 90.05508339234207, + 93.212547840127741 + ], + [ + 89.739256687409153, + 93.620894900035168 + ], + [ + 89.418695473095624, + 94.026845409121847 + ], + [ + 89.09435819686864, + 94.429768623966439 + ], + [ + 88.768133459736134, + 94.832892483970838 + ], + [ + 88.442398864608577, + 95.233053585402388 + ], + [ + 88.1178663775948, + 95.626945770262338 + ], + [ + 87.79526565646826, + 96.011552277333834 + ], + [ + 87.460891058759756, + 96.407432299242046 + ], + [ + 87.128880670332222, + 96.798971228228254 + ], + [ + 86.79850235162651, + 97.188693705769069 + ], + [ + 86.468747752190069, + 97.571495632329061 + ], + [ + 86.1391482452388, + 97.948686007595427 + ], + [ + 85.796473124737091, + 98.33508167662977 + ], + [ + 85.453956645157149, + 98.71823192852014 + ], + [ + 85.121810226318118, + 99.094702754866859 + ], + [ + 84.784327932845486, + 99.4748986456793 + ], + [ + 84.449967133418468, + 99.846955002402822 + ], + [ + 84.109706983369719, + 100.2268372899343 + ], + [ + 83.769383927709754, + 100.60244887960513 + ], + [ + 83.425332938634483, + 100.98541523292353 + ], + [ + 83.084694340962159, + 101.37006454818528 + ], + [ + 82.752816507415318, + 101.74766153607415 + ], + [ + 82.415386124205583, + 102.13364167031801 + ], + [ + 82.076287757698367, + 102.51343181097411 + ], + [ + 81.731934874059277, + 102.89891982955795 + ], + [ + 81.395895457823272, + 103.27753305559929 + ], + [ + 81.062084407067516, + 103.65658679546941 + ], + [ + 80.726147455681371, + 104.04444693239914 + ], + [ + 80.395734345073649, + 104.42796268135378 + ], + [ + 80.070291236065117, + 104.80883866898303 + ], + [ + 79.739247352877669, + 105.20274905993148 + ], + [ + 79.414212452068426, + 105.59393005567785 + ], + [ + 79.091892418296467, + 105.9802274459436 + ], + [ + 78.7679343655284, + 106.37658559354581 + ], + [ + 78.4598990342672, + 106.77506636922618 + ], + [ + 78.1513129866323, + 107.18689522801228 + ], + [ + 77.850121564824263, + 107.59698090133348 + ], + [ + 77.5525502083743, + 108.00018131439273 + ], + [ + 77.252130002741467, + 108.41324892813503 + ], + [ + 76.9660049512181, + 108.83846283103046 + ], + [ + 76.6837140734195, + 109.25466073263581 + ], + [ + 76.3913597850261, + 109.67028557887599 + ], + [ + 76.105130624705055, + 110.08732628606622 + ], + [ + 75.829453934246985, + 110.5058362299884 + ], + [ + 75.549613143375225, + 110.93044963123934 + ], + [ + 75.275766692361842, + 111.35005843436144 + ], + [ + 74.994923968943937, + 111.77854526368597 + ], + [ + 74.701142719431317, + 112.19385332827 + ], + [ + 74.387841165293537, + 112.60271900385499 + ], + [ + 74.063697381977363, + 112.98907664939419 + ], + [ + 73.719516435792627, + 113.35755732909838 + ], + [ + 73.375673718911514, + 113.72294161211082 + ], + [ + 73.030683194846262, + 114.09468651465917 + ], + [ + 72.67800308169798, + 114.46892030679416 + ], + [ + 72.336539588609668, + 114.83935428791028 + ], + [ + 71.997735672070988, + 115.22070601117387 + ], + [ + 71.670569195013329, + 115.60014570799238 + ], + [ + 71.343166025955824, + 115.98434748578553 + ], + [ + 71.011196985797127, + 116.37268265836013 + ], + [ + 70.67536391990555, + 116.76377589541407 + ], + [ + 70.351497684059169, + 117.14723800853257 + ], + [ + 70.022552265437184, + 117.52984470581421 + ], + [ + 69.687550175273543, + 117.91151320027578 + ], + [ + 69.352202953717637, + 118.29993057456133 + ], + [ + 69.019299045354359, + 118.69636465858623 + ], + [ + 68.699940246144635, + 119.0826732830206 + ], + [ + 68.382359614998748, + 119.47418717184011 + ], + [ + 68.068735098584909, + 119.87450160913669 + ], + [ + 67.757112931571456, + 120.28141879369379 + ], + [ + 67.44956514267632, + 120.69379781502781 + ], + [ + 67.143063429660458, + 121.11010655482903 + ], + [ + 66.837304312084441, + 121.53051011212213 + ], + [ + 66.5451356694342, + 121.9378128398883 + ], + [ + 66.25300469301088, + 122.34809864107835 + ], + [ + 65.964277519630485, + 122.76128246377222 + ], + [ + 65.677337794080557, + 123.17656392774519 + ], + [ + 65.395099671323734, + 123.59600392951383 + ], + [ + 65.116361183287751, + 124.01952523888389 + ], + [ + 64.840188157365489, + 124.44541401255896 + ], + [ + 64.56331681562159, + 124.87253809511533 + ], + [ + 64.286351373936412, + 125.30112444090366 + ], + [ + 64.007298285423715, + 125.73125784115135 + ], + [ + 63.7255546182783, + 126.16050451256079 + ], + [ + 63.4401859907007, + 126.58730759722559 + ], + [ + 63.153310514701388, + 127.00950840038139 + ], + [ + 62.86869528090164, + 127.42903909712059 + ], + [ + 62.586350474202725, + 127.84451848443507 + ], + [ + 62.29322096629793, + 128.27235368670347 + ], + [ + 62.002212951863264, + 128.69724811057543 + ], + [ + 61.714794665541895, + 129.12017692627202 + ], + [ + 61.432206082296496, + 129.54220772580996 + ], + [ + 61.152658979010873, + 129.96212646611141 + ], + [ + 60.870385239245174, + 130.38182361276017 + ], + [ + 60.586310933862691, + 130.80566400557819 + ], + [ + 60.303779693209314, + 131.22563048558433 + ], + [ + 60.014083865825889, + 131.65312774728344 + ], + [ + 59.726867316476074, + 132.07178561360678 + ], + [ + 59.439423891173426, + 132.485097135448 + ], + [ + 59.142254490390044, + 132.90960859487296 + ], + [ + 58.847383502107483, + 133.32710031176973 + ], + [ + 58.553356626656893, + 133.73711853247639 + ], + [ + 58.252960254654361, + 134.1517439172608 + ], + [ + 57.947619845584555, + 134.56361937600013 + ], + [ + 57.640679250003785, + 134.9713706216304 + ], + [ + 57.33746609468929, + 135.3789303851168 + ], + [ + 57.03331182338674, + 135.78575451506046 + ], + [ + 56.721125710328806, + 136.19013773408804 + ], + [ + 56.4076544874232, + 136.5869642414842 + ], + [ + 56.084132508801943, + 136.98703962447468 + ], + [ + 55.765791768993516, + 137.37654076164523 + ], + [ + 55.454966739055806, + 137.76885206629106 + ], + [ + 55.147731057605405, + 138.17770933326634 + ], + [ + 54.858859764640407, + 138.59630993800352 + ], + [ + 54.584396290135807, + 139.01687236733861 + ], + [ + 54.323252708695208, + 139.44684308734753 + ], + [ + 54.0837019092609, + 139.88733437806243 + ], + [ + 53.885223377595757, + 140.35050743670806 + ], + [ + 53.746723948394958, + 140.83575615492049 + ], + [ + 53.673002676975592, + 141.33196128662175 + ], + [ + 53.659063015386323, + 141.83724342124293 + ], + [ + 53.739457531948084, + 142.33897715986785 + ], + [ + 53.89936532178109, + 142.81540423490762 + ], + [ + 54.143914170131183, + 143.25972167059499 + ], + [ + 54.471841069538684, + 143.63883061752262 + ], + [ + 54.87064714643995, + 143.94810735778663 + ], + [ + 55.317505252715684, + 144.17751354372706 + ], + [ + 55.793376133966191, + 144.34589712897 + ], + [ + 56.281626821626496, + 144.47321821650667 + ], + [ + 56.766263408668607, + 144.60791950116735 + ], + [ + 57.241249073000681, + 144.77547236703731 + ], + [ + 57.709100722550637, + 144.97549039072143 + ], + [ + 58.1634273713367, + 145.2050277671124 + ], + [ + 58.607824632195843, + 145.4558348970979 + ], + [ + 59.040999391237108, + 145.71907903327852 + ], + [ + 59.464768075694984, + 145.98563616769062 + ], + [ + 59.894549206070351, + 146.26897184455751 + ], + [ + 60.307790429713556, + 146.55243424236923 + ], + [ + 60.730234683418686, + 146.84738234222834 + ], + [ + 61.141645621659734, + 147.15039611395369 + ], + [ + 61.538879905464562, + 147.4661113559861 + ], + [ + 61.927275742175418, + 147.78449222754162 + ], + [ + 62.325545974619338, + 148.10721357218259 + ], + [ + 62.71097336289634, + 148.42961716899956 + ], + [ + 63.100007030515386, + 148.76809463386607 + ], + [ + 63.482291098508092, + 149.10143277874218 + ], + [ + 63.863900147397224, + 149.44752214598555 + ], + [ + 64.2328840991804, + 149.78921330068317 + ], + [ + 64.6066186737879, + 150.13817224297773 + ], + [ + 64.9855573185225, + 150.49396012540936 + ], + [ + 65.3454734133084, + 150.84521817572755 + ], + [ + 65.704673008297647, + 151.20662558257124 + ], + [ + 66.064756965225087, + 151.57473879164104 + ], + [ + 66.414878081054269, + 151.93400344051392 + ], + [ + 66.769892384523075, + 152.29956301249197 + ], + [ + 67.128858510746468, + 152.66925191486993 + ], + [ + 67.490958860452267, + 153.04137681560351 + ], + [ + 67.8440832532857, + 153.40003708186171 + ], + [ + 68.198838956706652, + 153.7640437903103 + ], + [ + 68.55496383859564, + 154.13461895145409 + ], + [ + 68.910633985007479, + 154.51054817522953 + ], + [ + 69.267828537635026, + 154.89101542457627 + ], + [ + 69.617704024271021, + 155.26798674659827 + ], + [ + 69.962887899263322, + 155.63860001036639 + ], + [ + 70.306392123186811, + 156.00454573751134 + ], + [ + 70.663906755969961, + 156.38593672632371 + ], + [ + 71.014630521659527, + 156.75668074221241 + ], + [ + 71.372621222527059, + 157.13296202221488 + ], + [ + 71.7373828134706, + 157.50507603147216 + ], + [ + 72.1049746078484, + 157.86711749865953 + ], + [ + 72.4720928754797, + 158.22007513369985 + ], + [ + 72.841082731265615, + 158.57123411108918 + ], + [ + 73.206338417055562, + 158.91952819303 + ], + [ + 73.583327165846939, + 159.28038083740157 + ], + [ + 73.958223284658118, + 159.63565249449408 + ], + [ + 74.338059191332491, + 159.98380905471814 + ], + [ + 74.72006418553616, + 160.32665251117606 + ], + [ + 75.101717496307216, + 160.66287357632373 + ], + [ + 75.49165409847835, + 160.98757170663848 + ], + [ + 75.886985847346367, + 161.30194035099817 + ], + [ + 76.279616573131378, + 161.61305230171126 + ], + [ + 76.685568773248747, + 161.93453757725681 + ], + [ + 77.091082558948088, + 162.25616709276846 + ], + [ + 77.494543881897741, + 162.57369781256995 + ], + [ + 77.903305276397987, + 162.88125280666816 + ], + [ + 78.317706269722208, + 163.17811704528384 + ], + [ + 78.728194291295949, + 163.46949507913408 + ], + [ + 79.149095657069722, + 163.77239790493914 + ], + [ + 79.566053556668351, + 164.06892658344393 + ], + [ + 79.979944440319485, + 164.36381976924096 + ], + [ + 80.399356888291052, + 164.66540403452137 + ], + [ + 80.807529373361987, + 164.96077516733757 + ], + [ + 81.217331028049344, + 165.26592066883777 + ], + [ + 81.618802797339654, + 165.57391876161645 + ], + [ + 82.013149309557974, + 165.8879907238555 + ], + [ + 82.395381711216686, + 166.21385577878661 + ], + [ + 82.776815219540723, + 166.56202033208058 + ], + [ + 83.146651335636008, + 166.91666717906381 + ], + [ + 83.508598197731146, + 167.27053114951417 + ], + [ + 83.8643756117052, + 167.62463690392733 + ], + [ + 84.212387964188352, + 167.98369692233504 + ], + [ + 84.5627498350912, + 168.35602248372237 + ], + [ + 84.914829308806375, + 168.71902568059673 + ], + [ + 85.26887797773874, + 169.07561132810446 + ], + [ + 85.627998834419884, + 169.43164005260823 + ], + [ + 85.9918541130161, + 169.7786274953688 + ], + [ + 86.37453512625369, + 170.12593644442754 + ], + [ + 86.750214934008781, + 170.45950807119436 + ], + [ + 87.132300249306255, + 170.78899925721973 + ], + [ + 87.525159843252482, + 171.11349190143449 + ], + [ + 87.922457069651912, + 171.43988457663622 + ], + [ + 88.315418027937085, + 171.77050807407568 + ], + [ + 88.706614986638741, + 172.09862798938354 + ], + [ + 89.105267604722229, + 172.41929191392072 + ], + [ + 89.511300310818527, + 172.73384928632 + ], + [ + 89.922621917134421, + 173.04223838638757 + ], + [ + 90.340323540716057, + 173.34409736150579 + ], + [ + 90.76475443422926, + 173.64089711872722 + ], + [ + 91.176743050431554, + 173.92651108497554 + ], + [ + 91.590179465214931, + 174.21192237390088 + ], + [ + 92.007579767371723, + 174.49461195807908 + ], + [ + 92.424305102769921, + 174.77654790670744 + ], + [ + 92.834861647761429, + 175.06240051611911 + ], + [ + 93.261225646080817, + 175.35762753815934 + ], + [ + 93.689976414494751, + 175.64908042971229 + ], + [ + 94.1174973573749, + 175.93804416900403 + ], + [ + 94.5451332770183, + 176.22199938055417 + ], + [ + 94.97130142674375, + 176.50328138348326 + ], + [ + 95.3939450032775, + 176.79141718439965 + ], + [ + 95.816736039953241, + 177.08494939763565 + ], + [ + 96.237297198839926, + 177.38161338078905 + ], + [ + 96.651403238493714, + 177.67780950780755 + ], + [ + 97.059785095749348, + 177.97203947791482 + ], + [ + 97.466729610463517, + 178.26794054550734 + ], + [ + 97.875456791095417, + 178.56916767017634 + ], + [ + 98.290456971928677, + 178.86912463920888 + ], + [ + 98.706213106901146, + 179.15894824453619 + ], + [ + 99.118686453101191, + 179.44264521848649 + ], + [ + 99.542749345735231, + 179.73355403672434 + ], + [ + 99.960876616351072, + 180.02386566865218 + ], + [ + 100.37851904792558, + 180.30983360972792 + ], + [ + 100.79875690774676, + 180.58516096535047 + ], + [ + 101.23440753398397, + 180.8634382622586 + ], + [ + 101.6648087469364, + 181.13539066352931 + ], + [ + 102.09578240534817, + 181.3921634179803 + ], + [ + 102.53061784134283, + 181.63913104919658 + ], + [ + 102.98233284196323, + 181.88586196553644 + ], + [ + 103.43467761480888, + 182.12107277147916 + ], + [ + 103.89586081642113, + 182.352947838741 + ], + [ + 104.35338965783781, + 182.57184126861802 + ], + [ + 104.81451258067168, + 182.7797583777899 + ], + [ + 105.27669737557019, + 182.97942297300418 + ], + [ + 105.73918050737966, + 183.17119655791933 + ], + [ + 106.21148582661594, + 183.36602822908341 + ], + [ + 106.67304434591054, + 183.56615893110916 + ], + [ + 107.14006246753571, + 183.77677682779475 + ], + [ + 107.59612297488846, + 183.99684777543885 + ], + [ + 108.03768098341237, + 184.23428772329439 + ], + [ + 108.46174029866138, + 184.50754244591067 + ], + [ + 108.87196259359304, + 184.81610950895788 + ], + [ + 109.2687570915941, + 185.12420990376253 + ], + [ + 109.66012603960313, + 185.45088020425177 + ], + [ + 110.06546900323926, + 185.76207443474004 + ], + [ + 110.47837898394847, + 186.05339502520405 + ], + [ + 110.89912606420207, + 186.3397207071508 + ], + [ + 111.32000865088645, + 186.62308591266682 + ], + [ + 111.74287450528625, + 186.90001198055182 + ], + [ + 112.17878675329273, + 187.17566925085126 + ], + [ + 112.61801407562032, + 187.43754634220159 + ], + [ + 113.05732355705142, + 187.6863070383092 + ], + [ + 113.50878848475838, + 187.93220994413818 + ], + [ + 113.94802031621153, + 188.17264280073511 + ], + [ + 114.39126376997712, + 188.42105605596223 + ], + [ + 114.84075639263682, + 188.67517279339515 + ], + [ + 115.28196065374773, + 188.92454093878595 + ], + [ + 115.73208023852143, + 189.17443464194665 + ], + [ + 116.17315775747012, + 189.41549331422661 + ], + [ + 116.61988832451823, + 189.66029419526473 + ], + [ + 117.07001876966086, + 189.91272687681985 + ], + [ + 117.50628927758831, + 190.15869679044729 + ], + [ + 117.95159041351516, + 190.40433204906427 + ], + [ + 118.4064146649705, + 190.65039551329906 + ], + [ + 118.86487506912755, + 190.89994482712692 + ], + [ + 119.30677902227005, + 191.14359709212707 + ], + [ + 119.75401331749778, + 191.38916081980656 + ], + [ + 120.20511461849412, + 191.63701238806482 + ], + [ + 120.66014533061603, + 191.89097040650665 + ], + [ + 121.09552515553922, + 192.14027890051091 + ], + [ + 121.53294480951409, + 192.39453048129872 + ], + [ + 121.97263953794329, + 192.65232342331683 + ], + [ + 122.41668283580803, + 192.91297337614711 + ], + [ + 122.85877183472442, + 193.17605002387757 + ], + [ + 123.29462644824724, + 193.43668935346713 + ], + [ + 123.72668988808427, + 193.69065494883836 + ], + [ + 124.1771280286459, + 193.95270768574812 + ], + [ + 124.62497000121654, + 194.21323361358006 + ], + [ + 125.07490504498225, + 194.46962420350874 + ], + [ + 125.52640955518743, + 194.72251114396138 + ], + [ + 125.97387874184888, + 194.97683079837768 + ], + [ + 126.4147021453275, + 195.23538381231396 + ], + [ + 126.84405918119019, + 195.49665925079398 + ], + [ + 127.28927909094345, + 195.76771518347033 + ], + [ + 127.733268536591, + 196.03798593360415 + ], + [ + 128.17669600723517, + 196.30767577140628 + ], + [ + 128.61574704521573, + 196.57850289291318 + ], + [ + 129.04908896350878, + 196.85194680652552 + ], + [ + 129.4778652458777, + 197.12815859711159 + ], + [ + 129.90197066855262, + 197.40336744765617 + ], + [ + 130.32144045388853, + 197.67919212941109 + ], + [ + 130.75144031980838, + 197.97259973087475 + ], + [ + 131.1681032445378, + 198.27588395349997 + ], + [ + 131.57602695441318, + 198.5863562663921 + ], + [ + 131.97656590903404, + 198.90189418838045 + ], + [ + 132.36634658370272, + 199.22259242250289 + ], + [ + 132.76369230640006, + 199.55881293757741 + ], + [ + 133.14783925065396, + 199.89945923542763 + ], + [ + 133.5203341277323, + 200.24629104724372 + ], + [ + 133.87367818006666, + 200.60963161090484 + ], + [ + 134.21317939743969, + 200.98679902195781 + ], + [ + 134.54145011385279, + 201.36773997638665 + ], + [ + 134.86708466699508, + 201.76576864977844 + ], + [ + 135.17348634330455, + 202.17136360721091 + ], + [ + 135.4692115088709, + 202.582263822625 + ], + [ + 135.74662015983969, + 203.00239404132725 + ], + [ + 136.01328942351361, + 203.44618216766131 + ], + [ + 136.27493689755903, + 203.88527344642895 + ], + [ + 136.52839569749517, + 204.32384854241096 + ], + [ + 136.76834877228458, + 204.76484149515761 + ], + [ + 137.01374170511619, + 205.22003163885296 + ], + [ + 137.25979021858342, + 205.67034682787781 + ], + [ + 137.50404398705575, + 206.11898996394433 + ], + [ + 137.74960709611577, + 206.56241315286397 + ], + [ + 137.99558754414693, + 207.01693196650112 + ], + [ + 138.2330302796093, + 207.4701070320512 + ], + [ + 138.46152172760634, + 207.92519648535816 + ], + [ + 138.67498516299821, + 208.38130888797844 + ], + [ + 138.89023426015658, + 208.84994577949772 + ], + [ + 139.10857899673857, + 209.31236968104139 + ], + [ + 139.32467443061731, + 209.76883019585415 + ], + [ + 139.53813308230627, + 210.23637745459831 + ], + [ + 139.73511045518239, + 210.70194954624441 + ], + [ + 139.90946064711957, + 211.17065239076823 + ], + [ + 140.05887124810508, + 211.65816012452666 + ], + [ + 140.1778109622627, + 212.15846788203646 + ], + [ + 140.25714853593837, + 212.65655275559053 + ], + [ + 140.2961286540351, + 213.16558927267994 + ], + [ + 140.2897856458373, + 213.67771500701531 + ], + [ + 140.23593291746809, + 214.18156098469049 + ], + [ + 140.13120057894531, + 214.67246398824344 + ], + [ + 139.98548647881225, + 215.15804432974699 + ], + [ + 139.796080960416, + 215.63369020256474 + ], + [ + 139.5737714778283, + 216.09578652030115 + ], + [ + 139.337468558432, + 216.54290813507242 + ], + [ + 139.07482444923136, + 216.9770669842753 + ], + [ + 138.79382829418958, + 217.40563559026376 + ], + [ + 138.50013500174021, + 217.814983217427 + ], + [ + 138.18056210813609, + 218.21268062283846 + ], + [ + 137.83308910732291, + 218.58785228625732 + ], + [ + 137.47262069625916, + 218.95238515538773 + ], + [ + 137.10166668087018, + 219.30998891630046 + ], + [ + 136.73070654202053, + 219.64533104684568 + ], + [ + 136.363801760048, + 219.99544161049192 + ], + [ + 135.99440122360161, + 220.35010281033854 + ], + [ + 135.61630231267938, + 220.70071906013754 + ], + [ + 135.25314814173234, + 221.05156508740316 + ], + [ + 134.88715201488841, + 221.4062444407696 + ], + [ + 134.5161252236955, + 221.75855214499694 + ], + [ + 134.14122543687211, + 222.10661964764356 + ], + [ + 133.76522433813389, + 222.45200047763211 + ], + [ + 133.3923843869288, + 222.79715711398188 + ], + [ + 133.02752279856665, + 223.14984563899432 + ], + [ + 132.67028397940317, + 223.51050706013982 + ], + [ + 132.3163149773344, + 223.87924844201649 + ], + [ + 131.96447559521604, + 224.25706291983931 + ], + [ + 131.62295685300475, + 224.62318756958354 + ], + [ + 131.26370509672873, + 224.98899845797189 + ], + [ + 130.8999775267468, + 225.34583038768406 + ], + [ + 130.53624274080016, + 225.70371706527831 + ], + [ + 130.17761770341247, + 226.06586172688563 + ], + [ + 129.82138198367062, + 226.42739152322042 + ], + [ + 129.46685390488412, + 226.7825028384797 + ], + [ + 129.11858513186272, + 227.14384280962815 + ], + [ + 128.77740530235755, + 227.51097008812971 + ], + [ + 128.42683937109885, + 227.88873247434708 + ], + [ + 128.07619019947529, + 228.2555297381542 + ], + [ + 127.71716065019317, + 228.62173610703587 + ], + [ + 127.37018904401732, + 228.98986830598986 + ], + [ + 127.01774410841912, + 229.36236371057265 + ], + [ + 126.67522230398801, + 229.73618032479553 + ], + [ + 126.32594024046352, + 230.11107035815371 + ], + [ + 125.98262981706569, + 230.479177509143 + ], + [ + 125.64988089239935, + 230.85325853088062 + ], + [ + 125.31894207557804, + 231.24611787587568 + ], + [ + 125.00370419378277, + 231.63423680888278 + ], + [ + 124.68234093491897, + 232.03322678090848 + ], + [ + 124.36761455619167, + 232.43479344210959 + ], + [ + 124.04794693957892, + 232.8262772896945 + ], + [ + 123.72064440710228, + 233.22212882001873 + ], + [ + 123.40179084981864, + 233.62061066185362 + ], + [ + 123.08159410928208, + 234.01233321146685 + ], + [ + 122.75465697539006, + 234.40771587706774 + ], + [ + 122.42868028350745, + 234.79689041342419 + ], + [ + 122.10089819105789, + 235.18463402516838 + ], + [ + 121.75879658475405, + 235.55866534971574 + ], + [ + 121.40176483474622, + 235.91187025417543 + ], + [ + 121.02583858201575, + 236.25672604899717 + ], + [ + 120.64907485724353, + 236.59773544827243 + ], + [ + 120.2692813115935, + 236.93153307665949 + ], + [ + 119.89080381006556, + 237.26398194930476 + ], + [ + 119.50147743027894, + 237.59573972256848 + ], + [ + 119.11556264549978, + 237.9248246469914 + ], + [ + 118.73392803556422, + 238.25642875980057 + ], + [ + 118.35715239467545, + 238.59318674773172 + ], + [ + 117.99477241711405, + 238.93930473570822 + ], + [ + 117.63803670949422, + 239.29039897988423 + ], + [ + 117.27956161036086, + 239.65377141922707 + ], + [ + 116.93147867322094, + 240.02355689261404 + ], + [ + 116.58441393961867, + 240.3854755523102 + ], + [ + 116.2298879921529, + 240.74948497718012 + ], + [ + 115.88694388256289, + 241.11341919525194 + ], + [ + 115.54695176939357, + 241.48330800187182 + ], + [ + 115.2023773303262, + 241.86061972002494 + ], + [ + 114.88140403052387, + 242.25104046479004 + ], + [ + 114.56981269321025, + 242.65309057094544 + ], + [ + 114.2710918458496, + 243.05666614222631 + ], + [ + 113.97910499686654, + 243.47241746111331 + ], + [ + 113.67766547749662, + 243.88296149382572 + ], + [ + 113.36835007418515, + 244.29005114662564 + ], + [ + 113.05844629368268, + 244.69815444189209 + ], + [ + 112.75751448308542, + 245.10877531177692 + ], + [ + 112.4805930131879, + 245.52875558545236 + ], + [ + 112.20551848489708, + 245.94732024826334 + ], + [ + 111.93646050754323, + 246.37981172542195 + ], + [ + 111.69639538047436, + 246.82849053735794 + ], + [ + 111.4655646063777, + 247.28305790197285 + ], + [ + 111.26609420950877, + 247.74354303271153 + ], + [ + 111.07002935038376, + 248.21115398745951 + ], + [ + 110.87828309975737, + 248.67475798825547 + ], + [ + 110.68996745319062, + 249.1462275949321 + ], + [ + 110.52599882850608, + 249.62334525054334 + ], + [ + 110.39669722759695, + 250.1063633328157 + ], + [ + 110.251497505906, + 250.58638282484472 + ], + [ + 110.04871017618638, + 251.04596839926512 + ], + [ + 109.77218372349618, + 251.462890650187 + ], + [ + 109.45496411102413, + 251.85758517640738 + ], + [ + 109.09331314149796, + 252.21868308285133 + ], + [ + 108.70524213046032, + 252.55085738240626 + ], + [ + 108.31287715301518, + 252.86432340042163 + ], + [ + 107.91773146603984, + 253.17297920752952 + ], + [ + 107.51841192338539, + 253.49231942189633 + ], + [ + 107.12550616480516, + 253.80572966851995 + ], + [ + 106.74154781972639, + 254.12820844665606 + ], + [ + 106.36054596468884, + 254.45872495089301 + ], + [ + 105.97289939966186, + 254.79158837686939 + ], + [ + 105.59431317670043, + 255.12849272822942 + ], + [ + 105.2249736872278, + 255.47515961247885 + ], + [ + 104.85798906667473, + 255.82831769590345 + ], + [ + 104.49323149102595, + 256.18697259571803 + ], + [ + 104.13625660594708, + 256.55202526360711 + ], + [ + 103.78231121946254, + 256.90978793495418 + ], + [ + 103.41499377593686, + 257.26779276606476 + ], + [ + 103.05299070630453, + 257.62354087112033 + ], + [ + 102.68985349186696, + 257.99228195721048 + ], + [ + 102.3363850029192, + 258.35263683055251 + ], + [ + 101.9786898057374, + 258.72421228746225 + ], + [ + 101.63363518407034, + 259.09114548685164 + ], + [ + 101.28295823572167, + 259.47006836806429 + ], + [ + 100.9431657884526, + 259.85418847103608 + ], + [ + 100.60811936739921, + 260.23645866636605 + ], + [ + 100.27638183700273, + 260.61201972796175 + ], + [ + 99.943618295304248, + 261.00136921090416 + ], + [ + 99.616338786208757, + 261.38588228111956 + ], + [ + 99.28368518993905, + 261.77695023043094 + ], + [ + 98.954574858123, + 262.15961265936335 + ], + [ + 98.619894962092872, + 262.53511007970343 + ], + [ + 98.286547693449108, + 262.91891833916856 + ], + [ + 97.952843036737917, + 263.30973405003306 + ], + [ + 97.631611994455881, + 263.69783144610852 + ], + [ + 97.313659846989452, + 264.08734381399944 + ], + [ + 96.996500518056578, + 264.48129176600213 + ], + [ + 96.676660666989221, + 264.8776873995273 + ], + [ + 96.363995508191366, + 265.27687315411754 + ], + [ + 96.059135414805922, + 265.67544774850512 + ], + [ + 95.754935959342461, + 266.07320584225033 + ], + [ + 95.54500910139032, + 266.5283217335255 + ], + [ + 95.3396426885443, + 266.98242535102605 + ], + [ + 95.08134429387529, + 267.41614164660086 + ], + [ + 94.719353351022477, + 267.76627122437304 + ], + [ + 94.3843172213832, + 268.14094605436321 + ], + [ + 94.05195840633067, + 268.52433506035715 + ], + [ + 93.685254471940453, + 268.87189517528162 + ], + [ + 93.340410878657238, + 269.23493278423109 + ], + [ + 93.0045767897574, + 269.61650195058957 + ], + [ + 92.685017978508, + 270.00398195013213 + ], + [ + 92.352779340967345, + 270.391583779759 + ], + [ + 92.022455321679516, + 270.78307865897392 + ], + [ + 91.703070149827582, + 271.18125393881394 + ], + [ + 91.382737414756022, + 271.57323146254669 + ], + [ + 91.079294658078723, + 271.98397645660759 + ], + [ + 90.7850898764009, + 272.39428985334268 + ], + [ + 90.4920315163895, + 272.80206101349461 + ], + [ + 90.211099451136093, + 273.21671132131883 + ], + [ + 89.926351695797791, + 273.64212143027413 + ], + [ + 89.640524130059035, + 274.05829610526052 + ], + [ + 89.3463746618479, + 274.4827073175457 + ], + [ + 89.0577620935151, + 274.90352034913064 + ], + [ + 88.7745253670829, + 275.31683269226562 + ], + [ + 88.4843689181456, + 275.73670835723459 + ], + [ + 88.198893582163933, + 276.14807026552461 + ], + [ + 87.907867529726275, + 276.56416540775717 + ], + [ + 87.609568465023727, + 276.98184412316505 + ], + [ + 87.319044599323519, + 277.39150114519316 + ], + [ + 87.027255952198033, + 277.80981055160925 + ], + [ + 86.727935334806062, + 278.22943755385768 + ], + [ + 86.439576559800457, + 278.63976019312105 + ], + [ + 86.15337998185467, + 279.05997807954662 + ], + [ + 85.8639232721739, + 279.48476174069225 + ], + [ + 85.568602114862742, + 279.91031054909178 + ], + [ + 85.290715969257434, + 280.32982704611055 + ], + [ + 85.017202503310571, + 280.75968105054636 + ], + [ + 84.741109814330272, + 281.19253370183822 + ], + [ + 84.4628144764784, + 281.62951336038816 + ], + [ + 84.206195912678766, + 282.05916047232012 + ], + [ + 83.954547974046932, + 282.49542198377912 + ], + [ + 83.701405698102718, + 282.92736888956591 + ], + [ + 83.436015738362329, + 283.37040515735021 + ], + [ + 83.1718113412434, + 283.80615658681268 + ], + [ + 82.907907289388262, + 284.2378995747967 + ], + [ + 82.642127187050264, + 284.6653232097654 + ], + [ + 82.363412686065658, + 285.10422712843643 + ], + [ + 82.082143847006762, + 285.53528028174861 + ], + [ + 81.7994981447227, + 285.95985303599093 + ], + [ + 81.516385967828086, + 286.37849354607334 + ], + [ + 81.230151907021437, + 286.78924830814486 + ], + [ + 80.926295726762476, + 287.20755175388967 + ], + [ + 80.617774792969087, + 287.616250646093 + ], + [ + 80.308404917110607, + 288.0200578451844 + ], + [ + 80.0003889414236, + 288.41958237293716 + ], + [ + 79.676014369465335, + 288.82483672037893 + ], + [ + 79.349037869999378, + 289.22217948184613 + ], + [ + 79.019792652044472, + 289.61224074219962 + ], + [ + 78.686011861152977, + 289.99351557661419 + ], + [ + 78.349400343349018, + 290.36583755884823 + ], + [ + 78.00093421794746, + 290.74683932085014 + ], + [ + 77.6491902085606, + 291.11865881419027 + ], + [ + 77.290608467164788, + 291.47612473869594 + ], + [ + 76.910816314029034, + 291.82752373606382 + ], + [ + 76.514618838447419, + 292.14997974033838 + ], + [ + 76.112002442726464, + 292.44982043901109 + ], + [ + 75.69456570610113, + 292.73247037379139 + ], + [ + 75.2399439690916, + 292.97521985070966 + ], + [ + 74.759418251986773, + 293.1636354137039 + ], + [ + 74.278943799821292, + 293.32505547770353 + ], + [ + 73.788933000599854, + 293.45603511652769 + ], + [ + 73.284702213923154, + 293.55757217887276 + ], + [ + 72.789497144871959, + 293.64197829261883 + ], + [ + 72.277888570914655, + 293.70279561978589 + ], + [ + 71.767757804019439, + 293.73675562840259 + ], + [ + 71.2664589187814, + 293.75171910005417 + ], + [ + 70.756899242440866, + 293.75001753403575 + ], + [ + 70.243641378442319, + 293.72467968886156 + ], + [ + 69.727932966931462, + 293.67978023522335 + ], + [ + 69.224823405564166, + 293.62912759143444 + ], + [ + 68.71916413165907, + 293.57766429456137 + ], + [ + 68.210122644683622, + 293.52391777824732 + ], + [ + 67.694581114531715, + 293.46278583085473 + ], + [ + 67.195980245570013, + 293.40128474950615 + ], + [ + 66.69247422679031, + 293.337360788924 + ], + [ + 66.186455317480437, + 293.26224477547788 + ], + [ + 65.674382189387075, + 293.17395581092319 + ], + [ + 65.182433319875585, + 293.08444191670668 + ], + [ + 64.68797400089241, + 292.99292533374449 + ], + [ + 64.193709566215958, + 292.89534761195983 + ], + [ + 63.700264963740274, + 292.7861887926652 + ], + [ + 63.204954725924658, + 292.67264054278962 + ], + [ + 62.707707636836119, + 292.56419198620506 + ], + [ + 62.209038142765948, + 292.45685056537246 + ], + [ + 61.716350417575505, + 292.34874641935522 + ], + [ + 61.208602288230352, + 292.239312036253 + ], + [ + 60.704778126635453, + 292.13831575903743 + ], + [ + 60.205353757998218, + 292.03635224182068 + ], + [ + 59.713054274341964, + 291.9285888055208 + ], + [ + 59.223557825442164, + 291.82245042259689 + ], + [ + 58.716596002242639, + 291.71809778548248 + ], + [ + 58.2141655692107, + 291.61519582027563 + ], + [ + 57.716900038790428, + 291.51406525583621 + ], + [ + 57.224690108955507, + 291.41341929716032 + ], + [ + 56.718518125360461, + 291.30849075064305 + ], + [ + 56.217453888080726, + 291.202752099553 + ], + [ + 55.719781399269195, + 291.1041485540585 + ], + [ + 55.225897393656773, + 291.01242128019 + ], + [ + 54.719165199745916, + 290.91535748835065 + ], + [ + 54.219591212800992, + 290.81459677983071 + ], + [ + 53.727614050090608, + 290.71215303943666 + ], + [ + 53.223805408382553, + 290.60546990593957 + ], + [ + 52.726188474725589, + 290.49376233664947 + ], + [ + 52.236214848876195, + 290.37420802637774 + ], + [ + 51.736954027535923, + 290.24694341820327 + ], + [ + 51.243805186106577, + 290.11947742275242 + ], + [ + 50.758133510704987, + 289.99282906928289 + ], + [ + 50.260971328753833, + 289.86652743822123 + ], + [ + 49.769250148177214, + 289.7402996982575 + ], + [ + 49.284363889119525, + 289.61522180822351 + ], + [ + 48.79368130635676, + 289.49753140555583 + ], + [ + 48.299209890380709, + 289.38614513215958 + ], + [ + 47.797515524208549, + 289.27621424645076 + ], + [ + 47.301400601178415, + 289.17018561434134 + ], + [ + 46.795731772745683, + 289.07670073387897 + ], + [ + 46.294691118715143, + 288.98993856791054 + ], + [ + 45.792473546112376, + 288.90293411638021 + ], + [ + 45.290122331710187, + 288.81372673971293 + ], + [ + 44.7842551794241, + 288.72559418981785 + ], + [ + 44.277573777185737, + 288.63393699796552 + ], + [ + 43.782003651901157, + 288.55551248158611 + ], + [ + 43.275770117395204, + 288.4759313813413 + ], + [ + 42.7736172037391, + 288.393448078803 + ], + [ + 42.278806843206162, + 288.30814111296826 + ], + [ + 41.773520369252211, + 288.22820308298958 + ], + [ + 41.275405283215655, + 288.15086491537403 + ], + [ + 40.766638885547131, + 288.07638115770811 + ], + [ + 40.270515648975056, + 288.00096852983444 + ], + [ + 39.767077941839283, + 287.92239621891105 + ], + [ + 39.271656658587219, + 287.8520082682976 + ], + [ + 38.774947700397881, + 287.78744014153835 + ], + [ + 38.274274404089638, + 287.73611856942915 + ], + [ + 37.761904195233292, + 287.7008380879335 + ], + [ + 37.252231010372476, + 287.67300894098457 + ], + [ + 36.748636147683136, + 287.64918973812678 + ], + [ + 36.236522428098304, + 287.63057960009394 + ], + [ + 35.734503759790151, + 287.62007444195012 + ], + [ + 35.225643102038028, + 287.61807432730058 + ], + [ + 34.71362973832538, + 287.61938649292523 + ], + [ + 34.213313267990962, + 287.62911780263113 + ], + [ + 33.706538887693711, + 287.64825852077024 + ], + [ + 33.196732264958428, + 287.67033682352104 + ], + [ + 32.683480127252594, + 287.69770486272171 + ], + [ + 32.1842725573987, + 287.73060975118852 + ], + [ + 31.679959472932403, + 287.76542583313375 + ], + [ + 31.171816992802363, + 287.80272733965921 + ], + [ + 30.66105992214943, + 287.83996041549943 + ], + [ + 30.14551995461958, + 287.87781750405372 + ], + [ + 29.644350336603608, + 287.91610103164305 + ], + [ + 29.137207208844096, + 287.9529646149295 + ], + [ + 28.624660297345041, + 287.97859573030064 + ], + [ + 28.106177931774081, + 287.98446390449271 + ], + [ + 27.586672264533455, + 287.98188093663958 + ], + [ + 27.068268515232266, + 287.98196639863278 + ], + [ + 26.551438270200912, + 287.97887554490319 + ], + [ + 26.034793169984336, + 287.9740592574932 + ], + [ + 25.515111914421738, + 287.97228077555582 + ], + [ + 25.015088249843803, + 287.97215253187693 + ], + [ + 24.502045510158904, + 287.97093047433242 + ], + [ + 23.998489466148033, + 287.96323121391515 + ], + [ + 23.497620152269246, + 287.95135431594656 + ], + [ + 22.980659060385744, + 287.93239939769956 + ], + [ + 22.469690046314977, + 287.90675034793151 + ], + [ + 21.96336775028923, + 287.8732178274318 + ], + [ + 21.458158592653223, + 287.83445609124561 + ], + [ + 20.958021415820291, + 287.79213775307261 + ], + [ + 20.449049932021477, + 287.74644095175483 + ], + [ + 19.948549760665919, + 287.6921485213274 + ], + [ + 19.436041864639115, + 287.62744276535585 + ], + [ + 18.927368849960654, + 287.56929890220925 + ], + [ + 18.425524679943585, + 287.51297858314354 + ], + [ + 17.915991119452912, + 287.4487096071424 + ], + [ + 17.415636558271764, + 287.3915371509521 + ], + [ + 16.913924535818165, + 287.33612540482517 + ], + [ + 16.412419291521321, + 287.27332471426934 + ], + [ + 15.916374767081084, + 287.19883210665949 + ], + [ + 15.419895726579213, + 287.09087202730939 + ], + [ + 14.94492795798228, + 286.92977668371486 + ], + [ + 14.484786787639393, + 286.71551755693116 + ], + [ + 14.056598130730265, + 286.45640892413849 + ], + [ + 13.654716417400893, + 286.15259943021533 + ], + [ + 13.28457997229579, + 285.8036090718283 + ], + [ + 12.961477911460172, + 285.41250619461545 + ], + [ + 12.692791435607608, + 284.97587385334737 + ], + [ + 12.470468422558813, + 284.52729909813644 + ], + [ + 12.262427191657887, + 284.06855823135493 + ], + [ + 12.068600469867731, + 283.60334549912687 + ], + [ + 11.891306380464908, + 283.124334872875 + ], + [ + 11.723279840764388, + 282.64907678135586 + ], + [ + 11.569373777590149, + 282.16763563893625 + ], + [ + 11.436252668957259, + 281.681835521799 + ], + [ + 11.303166751391348, + 281.18306943186752 + ], + [ + 11.17560707408971, + 280.69244701692503 + ], + [ + 11.055104046616, + 280.19058032945929 + ], + [ + 10.942315842128636, + 279.69273340115728 + ], + [ + 10.836182853153982, + 279.20024234710985 + ], + [ + 10.731244340031179, + 278.69778995463378 + ], + [ + 10.619139716646007, + 278.20788608164355 + ], + [ + 10.501503962282866, + 277.71036479482683 + ], + [ + 10.385824038437601, + 277.20439871355779 + ], + [ + 10.274669219316799, + 276.71122437274488 + ], + [ + 10.158358422798454, + 276.21203542122134 + ], + [ + 10.04677758402908, + 275.7233756235517 + ], + [ + 9.9340699689148266, + 275.228812066112 + ], + [ + 9.8199989444259668, + 274.72966944873673 + ], + [ + 9.6968086313613675, + 274.22554996816558 + ], + [ + 9.5719399429413681, + 273.7378581220396 + ], + [ + 9.4439818370061364, + 273.24810099338515 + ], + [ + 9.3092648582360837, + 272.752772468534 + ], + [ + 9.1696144231304757, + 272.2514926938216 + ], + [ + 9.0338190652479522, + 271.76774997535381 + ], + [ + 8.8983929675508957, + 271.27906609809463 + ], + [ + 8.7632996929998743, + 270.7838577957433 + ], + [ + 8.6284574145916562, + 270.28307533916495 + ], + [ + 8.4932219247101841, + 269.77816334988574 + ], + [ + 8.3631943779596867, + 269.2928503584094 + ], + [ + 8.23366886062023, + 268.803379880313 + ], + [ + 8.1085620859499929, + 268.30887737598022 + ], + [ + 7.988470746067085, + 267.80703568119264 + ], + [ + 7.8700911371547146, + 267.30117226744437 + ], + [ + 7.7491432044363018, + 266.79225515766512 + ], + [ + 7.6338559109406923, + 266.30377916647649 + ], + [ + 7.52131562178502, + 265.809889605163 + ], + [ + 7.4098034093331, + 265.31150883808442 + ], + [ + 7.2970952272950314, + 264.81050948231893 + ], + [ + 7.1835404782206886, + 264.30616589265486 + ], + [ + 7.0737904928196791, + 263.79713168649408 + ], + [ + 6.97141245340439, + 263.28413910610573 + ], + [ + 6.8713484368760387, + 262.76991479701388 + ], + [ + 6.77188064607883, + 262.27947299957827 + ], + [ + 6.6679713411479051, + 261.78496916314481 + ], + [ + 6.5638468463388, + 261.28594350668459 + ], + [ + 6.4602487052766868, + 260.78188560641445 + ], + [ + 6.3529989243688005, + 260.27657690722526 + ], + [ + 6.2419910732124011, + 259.76985071438673 + ], + [ + 6.1317473935357372, + 259.2591498934047 + ], + [ + 6.0262046113298977, + 258.74407629808161 + ], + [ + 5.9283586054587962, + 258.25272554806634 + ], + [ + 5.828248899521749, + 257.75947236970472 + ], + [ + 5.7253568288680006, + 257.26383870907739 + ], + [ + 5.6243739789498521, + 256.76534397863833 + ], + [ + 5.5254632323657171, + 256.26470198688912 + ], + [ + 5.4265503287952006, + 255.76241811264671 + ], + [ + 5.3247402498361156, + 255.25879843971111 + ], + [ + 5.2217832504966077, + 254.75431263851135 + ], + [ + 5.1231480089427013, + 254.25363130813855 + ], + [ + 5.0287602982784048, + 253.75609213069475 + ], + [ + 4.9369999774400553, + 253.26252851270675 + ], + [ + 4.84235530047568, + 252.74462473672705 + ], + [ + 4.7492434335968738, + 252.22862416736197 + ], + [ + 4.6553045956531314, + 251.71410595528505 + ], + [ + 4.5601648360652058, + 251.20161371337053 + ], + [ + 4.4657030533782365, + 250.69164348319015 + ], + [ + 4.3709690526474239, + 250.18059636199325 + ], + [ + 4.27561140853992, + 249.66452071128057 + ], + [ + 4.1840397965222031, + 249.17086411295657 + ], + [ + 4.0918125179389415, + 248.67692913379619 + ], + [ + 3.9949871359089943, + 248.16083343514569 + ], + [ + 3.898397262728726, + 247.651449963453 + ], + [ + 3.7995919599553365, + 247.14537126534654 + ], + [ + 3.7027077201702938, + 246.63999726350517 + ], + [ + 3.6095493921758934, + 246.13503196284239 + ], + [ + 3.5197731099727481, + 245.63163513073667 + ], + [ + 3.4309579784537174, + 245.13225374133876 + ], + [ + 3.3403818314961429, + 244.63729959000818 + ], + [ + 3.2422740997736339, + 244.12078107744324 + ], + [ + 3.1425772732361446, + 243.60755405202906 + ], + [ + 3.0400199852475942, + 243.09759734344704 + ], + [ + 2.9382753252697293, + 242.59126252144694 + ], + [ + 2.8400103510186359, + 242.08783184112286 + ], + [ + 2.7447047627612373, + 241.58731765970126 + ], + [ + 2.6505122835523256, + 241.08988514604164 + ], + [ + 2.5572466398103333, + 240.59347322827887 + ], + [ + 2.4659174964121262, + 240.09891817245031 + ], + [ + 2.3765619783778162, + 239.60630184957867 + ], + [ + 2.28643277741388, + 239.0920239905804 + ], + [ + 2.2002603883906, + 238.58193783385678 + ], + [ + 2.1160606074726718, + 238.076642967338 + ], + [ + 2.0334082050861837, + 237.57469351765215 + ], + [ + 1.9522962665882304, + 237.07435431784467 + ], + [ + 1.8734446692240854, + 236.57594742983793 + ], + [ + 1.7979477819466436, + 236.07880254048135 + ], + [ + 1.725586871565131, + 235.58366526302135 + ], + [ + 1.6504122109238266, + 235.06742676169728 + ], + [ + 1.5754024336020853, + 234.5497407283878 + ], + [ + 1.5064096241759712, + 234.0520684135964 + ], + [ + 1.4410491837044313, + 233.55236949586646 + ], + [ + 1.3783239993799781, + 233.05255909173582 + ], + [ + 1.3187991326688362, + 232.55555334340085 + ], + [ + 1.2593390195694483, + 232.03829126470703 + ], + [ + 1.2006428248630456, + 231.52114667219675 + ], + [ + 1.1452802841246226, + 231.00129774540582 + ], + [ + 1.0983842638496368, + 230.50318888485185 + ], + [ + 1.0542491062957902, + 229.98111780735914 + ], + [ + 1.0132507090455483, + 229.45969024708629 + ], + [ + 0.97281810979571937, + 228.93898668720632 + ], + [ + 0.92966064395114512, + 228.41749057839763 + ], + [ + 0.887789610120565, + 227.91923267814687 + ], + [ + 0.84646549358662937, + 227.39801011495734 + ], + [ + 0.80676773665137924, + 226.87775789384372 + ], + [ + 0.76600952288862534, + 226.35800298681525 + ], + [ + 0.72098752481367967, + 225.83657067710365 + ], + [ + 0.67544205697318316, + 225.3151207149385 + ], + [ + 0.6311043418773673, + 224.79514621809395 + ], + [ + 0.58577872299978939, + 224.27650433971581 + ], + [ + 0.538174439087852, + 223.76010607777607 + ], + [ + 0.48761706229564661, + 223.24428282751637 + ], + [ + 0.43592730247645439, + 222.72981911861027 + ], + [ + 0.38349410604442019, + 222.21661910131056 + ], + [ + 0.32732265032817565, + 221.70365414622381 + ], + [ + 0.26453034796494335, + 221.18988565174217 + ], + [ + 0.20006864458005441, + 220.67640559496905 + ], + [ + 0.1350664337942753, + 220.16402014451936 + ], + [ + 0.067122816990140749, + 219.65239367291574 + ], + [ + -0.0044416782619387633, + 219.14101672917207 + ], + [ + -0.076767245919124608, + 218.63140665603262 + ], + [ + -0.14689630057182887, + 218.12339787363018 + ], + [ + -0.2164697244450208, + 217.61686333336826 + ], + [ + -0.28714265298703445, + 217.11236821726743 + ], + [ + -0.35958819680144111, + 216.60900732857564 + ], + [ + -0.43284813292189644, + 216.10714475752872 + ], + [ + -0.50683339385087456, + 215.60758559778367 + ], + [ + -0.58207379303581208, + 215.11245605708857 + ], + [ + -0.66340348674011018, + 214.60010227933856 + ], + [ + -0.751090069242837, + 214.09220332663693 + ], + [ + -0.84228371101933419, + 213.58743422165543 + ], + [ + -0.93383104026504826, + 213.08594664140489 + ], + [ + -1.026303289662875, + 212.58688843630694 + ], + [ + -1.1189637918101552, + 212.09252304108154 + ], + [ + -1.2174705480783041, + 211.5809461600995 + ], + [ + -1.3166563259747288, + 211.07211460422766 + ], + [ + -1.4145752625472543, + 210.56872404043958 + ], + [ + -1.514589851113141, + 210.06923853468288 + ], + [ + -1.615323527644233, + 209.57371911581765 + ], + [ + -1.7175128097615684, + 209.0829944271795 + ], + [ + -1.8235670677438207, + 208.5800752989648 + ], + [ + -1.9242768656935125, + 208.09016293404713 + ], + [ + -2.0292260824308879, + 207.59040612189051 + ], + [ + -2.1382364850295716, + 207.1017132575746 + ], + [ + -2.24439868739012, + 206.60472346047263 + ], + [ + -2.3432108738914006, + 206.09995339772789 + ], + [ + -2.4404254014246725, + 205.60916343097759 + ], + [ + -2.5432676966954864, + 205.11354997021385 + ], + [ + -2.6453161191522025, + 204.61421171596271 + ], + [ + -2.7505425650365862, + 204.11262546845248 + ], + [ + -2.8649270873277808, + 203.62465707871982 + ], + [ + -2.985478629638743, + 203.13158367184414 + ], + [ + -3.1146993898570545, + 202.63683548164812 + ], + [ + -3.2573599509711815, + 202.14411346443424 + ], + [ + -3.4046099017200739, + 201.6642867166037 + ], + [ + -3.559200141775952, + 201.18651793953791 + ], + [ + -3.7201985167709215, + 200.70290341343934 + ], + [ + -3.8884205335035498, + 200.23097830615677 + ], + [ + -4.0785623930076973, + 199.76045408738261 + ], + [ + -4.3042683233829377, + 199.30634903618704 + ], + [ + -4.5775294704659961, + 198.88665931239368 + ], + [ + -4.8943161093172831, + 198.49540518251953 + ], + [ + -5.2696030811390981, + 198.15885710592326 + ], + [ + -5.69766442724344, + 197.89254222586155 + ], + [ + -6.1737188231671833, + 197.73460092861586 + ], + [ + -6.67616125076763, + 197.70770468304445 + ], + [ + -7.1683284227749606, + 197.81629836025138 + ], + [ + -7.6376385203610289, + 197.98879839875005 + ], + [ + -8.0742538638458488, + 198.24378411395492 + ], + [ + -8.4992227472291919, + 198.514762031911 + ], + [ + -8.929681767565377, + 198.78498433618751 + ], + [ + -9.3804716705509712, + 199.01388506004443 + ], + [ + -9.849764875159611, + 199.19390215671652 + ], + [ + -10.334887838961333, + 199.31583376768523 + ], + [ + -10.828842294025915, + 199.40517951957844 + ], + [ + -11.325931214230815, + 199.46841477515716 + ], + [ + -11.829748543177821, + 199.505633514978 + ], + [ + -12.335576636710464, + 199.49906051890258 + ], + [ + -12.832884068215815, + 199.44586532164507 + ], + [ + -13.331730728608134, + 199.35821456275951 + ], + [ + -13.820990276678929, + 199.22121655552448 + ], + [ + -14.294923504366924, + 199.04006626295552 + ], + [ + -14.75220294519186, + 198.8245428149217 + ], + [ + -15.189413057568144, + 198.57838492312092 + ], + [ + -15.618798676156438, + 198.30137018326931 + ], + [ + -16.042557049931567, + 198.01588753943486 + ], + [ + -16.446266526243086, + 197.71968978994553 + ], + [ + -16.84932813527524, + 197.41300007080889 + ], + [ + -17.259803026811678, + 197.10577259550033 + ], + [ + -17.665472467954544, + 196.81303207248379 + ], + [ + -18.077679875356239, + 196.51634044901491 + ], + [ + -18.480039948122993, + 196.21273630651507 + ], + [ + -18.883065199498766, + 195.91316682726927 + ], + [ + -19.289816111666106, + 195.60429932470998 + ], + [ + -19.698071420785631, + 195.2921853185816 + ], + [ + -20.107155495419889, + 194.98517331518372 + ], + [ + -20.515516679113276, + 194.68608873392827 + ], + [ + -20.925029975639884, + 194.39813143565567 + ], + [ + -21.342268520918463, + 194.11225516035972 + ], + [ + -21.75838431924856, + 193.82670214196438 + ], + [ + -22.184123682182609, + 193.5401450628739 + ], + [ + -22.606959599451375, + 193.25091700890394 + ], + [ + -23.024898728140304, + 192.96608191889672 + ], + [ + -23.451099086936274, + 192.67694834617518 + ], + [ + -23.865742415123549, + 192.38359704223848 + ], + [ + -24.271905280216057, + 192.09029634213781 + ], + [ + -24.693270777338704, + 191.79789742030937 + ], + [ + -25.111489300051996, + 191.50982603403705 + ], + [ + -25.534033966996841, + 191.2168080862966 + ], + [ + -25.956337343262014, + 190.93056660511746 + ], + [ + -26.373809318163811, + 190.64915386747717 + ], + [ + -26.790003550816866, + 190.35428119289693 + ], + [ + -27.168242555198493, + 190.02672166657115 + ], + [ + -27.509577939234763, + 189.66070180936151 + ], + [ + -27.813949377746827, + 189.26232664518253 + ], + [ + -28.075303992758879, + 188.82776734511137 + ], + [ + -28.277556183493616, + 188.36125134254493 + ], + [ + -28.435230327460491, + 187.87904029537029 + ], + [ + -28.5365497719188, + 187.37679559334492 + ], + [ + -28.569028357421278, + 186.87053545777624 + ], + [ + -28.559975883567851, + 186.36007966401607 + ], + [ + -28.530556760115964, + 185.84830596746303 + ], + [ + -28.486639493637867, + 185.34708431217931 + ], + [ + -28.418384270449355, + 184.84047623491424 + ], + [ + -28.327293635050914, + 184.34059924454016 + ], + [ + -28.216633388533396, + 183.8518656957437 + ], + [ + -28.086633284150391, + 183.35840839520287 + ], + [ + -27.942411958897718, + 182.87706501775102 + ], + [ + -27.784877836177394, + 182.39176932084433 + ], + [ + -27.62823027754014, + 181.905878951555 + ], + [ + -27.460727995532284, + 181.4309419312238 + ], + [ + -27.283542705405697, + 180.94594421656922 + ], + [ + -27.105026005137844, + 180.47003550570304 + ], + [ + -26.916593694933031, + 180.00671909405529 + ], + [ + -26.726555053125917, + 179.53135904059752 + ], + [ + -26.5485357723579, + 179.05934587049114 + ], + [ + -26.3728555271588, + 178.57678812443265 + ], + [ + -26.201817483627583, + 178.1040959711751 + ], + [ + -26.0301220048621, + 177.62523076785294 + ], + [ + -25.852099940299965, + 177.14095626141685 + ], + [ + -25.669766203194406, + 176.67388885027899 + ], + [ + -25.481372145736561, + 176.1952668822411 + ], + [ + -25.297536576587127, + 175.724331434081 + ], + [ + -25.111095734096359, + 175.25917795538604 + ], + [ + -24.918264444237391, + 174.78160239679977 + ], + [ + -24.732241509104124, + 174.3047083385238 + ], + [ + -24.544590013627882, + 173.833326143458 + ], + [ + -24.356008082678063, + 173.36896395580951 + ], + [ + -24.169924420320449, + 172.90165173735639 + ], + [ + -23.97866129027933, + 172.42205719171483 + ], + [ + -23.789984066713828, + 171.94789097554605 + ], + [ + -23.600284878014893, + 171.46724832672493 + ], + [ + -23.412747017403625, + 170.98529104215766 + ], + [ + -23.226427441433291, + 170.51070828674293 + ], + [ + -23.044342056871223, + 170.04110278981804 + ], + [ + -22.859635506042419, + 169.55645178904439 + ], + [ + -22.673353911505419, + 169.0904447181465 + ], + [ + -22.484673672205233, + 168.62393339199181 + ], + [ + -22.294926515655224, + 168.14380645971741 + ], + [ + -22.107449779664847, + 167.6722750474033 + ], + [ + -21.919383256123819, + 167.20733708771616 + ], + [ + -21.730211363793273, + 166.72571343209881 + ], + [ + -21.547033367976194, + 166.24459414946097 + ], + [ + -21.365588286104984, + 165.76679970679604 + ], + [ + -21.189924983012244, + 165.29153381533433 + ], + [ + -21.017981795132158, + 164.8177528639 + ], + [ + -20.845377353184027, + 164.34316673339851 + ], + [ + -20.675365712558722, + 163.86804927774688 + ], + [ + -20.5129694745285, + 163.39128151922418 + ], + [ + -20.349046571765026, + 162.9177609762547 + ], + [ + -20.180734811074533, + 162.43588847042551 + ], + [ + -20.017138185057181, + 161.95628456358341 + ], + [ + -19.854426961312676, + 161.47976462039 + ], + [ + -19.687494057896007, + 160.99163623964509 + ], + [ + -19.522031954356947, + 160.50697780554552 + ], + [ + -19.357751559569348, + 160.02030734482773 + ], + [ + -19.195610837565486, + 159.54528958174853 + ], + [ + -19.030489736898986, + 159.06508848643182 + ], + [ + -18.861408082113638, + 158.58154552413294 + ], + [ + -18.685950005132753, + 158.09869261333813 + ], + [ + -18.508126231142949, + 157.61882787321881 + ], + [ + -18.333369653950896, + 157.14027532472744 + ], + [ + -18.161835920031475, + 156.6611209109951 + ], + [ + -17.993588017309175, + 156.18073397293424 + ], + [ + -17.826833692689629, + 155.70043795135493 + ], + [ + -17.65973486845791, + 155.22058603782676 + ], + [ + -17.492266286049649, + 154.74172803427771 + ], + [ + -17.325648573630577, + 154.26606141034338 + ], + [ + -17.15450183073667, + 153.77932946091966 + ], + [ + -16.98317152319358, + 153.29737402927842 + ], + [ + -16.805605460379674, + 152.82115662267765 + ], + [ + -16.622825493627367, + 152.34678776661025 + ], + [ + -16.439587185954366, + 151.86878575237586 + ], + [ + -16.255109978236217, + 151.38863794433269 + ], + [ + -16.065910470447225, + 150.91120829987719 + ], + [ + -15.874568207747236, + 150.43524997477252 + ], + [ + -15.682496208404002, + 149.95900129151485 + ], + [ + -15.493124748986439, + 149.4818627713635 + ], + [ + -15.310847714384298, + 149.001316701126 + ], + [ + -15.14196779954152, + 148.51570541430962 + ], + [ + -14.984565826961084, + 148.0278925058698 + ], + [ + -14.836346575167527, + 147.53818044892986 + ], + [ + -14.696651322175457, + 147.04935718663927 + ], + [ + -14.570135794901313, + 146.56409734891767 + ], + [ + -14.448762086947872, + 146.06611478036189 + ], + [ + -14.340808479441181, + 145.57263375023828 + ], + [ + -14.245669702733769, + 145.07926955095613 + ], + [ + -14.158373732460074, + 144.58685591681856 + ], + [ + -14.074372974121848, + 144.08359447648968 + ], + [ + -13.985690063973831, + 143.58949417898478 + ], + [ + -13.903603053174514, + 143.08325664855295 + ], + [ + -13.833775775154395, + 142.58067661238832 + ], + [ + -13.749988111518215, + 142.07406075864668 + ], + [ + -13.661188317843804, + 141.57513489806772 + ], + [ + -13.569026743375149, + 141.06985383216562 + ], + [ + -13.484781761267117, + 140.57163742725462 + ], + [ + -13.419459373855251, + 140.07524555905278 + ], + [ + -13.367334304645352, + 139.56940395446918 + ], + [ + -13.317297702430226, + 139.06085286750601 + ], + [ + -13.279863674889473, + 138.56218807624452 + ], + [ + -13.247451753862295, + 138.05761273950637 + ], + [ + -13.243468171977298, + 137.55265977034338 + ], + [ + -13.293752970164247, + 137.05231999658352 + ], + [ + -13.368651814523229, + 136.55094277819384 + ], + [ + -13.467241438379238, + 136.056653431316 + ], + [ + -13.630093221881973, + 135.58222269988318 + ], + [ + -13.875231369066738, + 135.14244409340904 + ], + [ + -14.163819559743915, + 134.73182175893226 + ], + [ + -14.532748813736383, + 134.38633182407739 + ], + [ + -14.968692082568808, + 134.14037598616119 + ], + [ + -15.418642638757094, + 133.92202670810607 + ], + [ + -15.886805400163583, + 133.7265378785396 + ], + [ + -16.365218350165755, + 133.5540394547221 + ], + [ + -16.853120234212831, + 133.44117095358462 + ], + [ + -17.345765070048223, + 133.3466619894717 + ], + [ + -17.8335373682257, + 133.23635996088552 + ], + [ + -18.323916471879357, + 133.09872094420021 + ], + [ + -18.81540640351098, + 132.98925028607164 + ], + [ + -19.302982492387518, + 132.85715566776187 + ], + [ + -19.792025453527479, + 132.74744601298477 + ], + [ + -20.295200158343583, + 132.69055652364267 + ], + [ + -20.799460146066568, + 132.63268979727354 + ], + [ + -21.294223784712841, + 132.5467782792586 + ], + [ + -21.787116117006931, + 132.43105927308426 + ], + [ + -22.272479730181121, + 132.31010766488964 + ], + [ + -22.761965465058022, + 132.17118511459088 + ], + [ + -23.241633939149313, + 132.00723284047058 + ], + [ + -23.712164261283082, + 131.81125238796207 + ], + [ + -24.152992096304757, + 131.57232137810124 + ], + [ + -24.588712950685778, + 131.30167565518784 + ], + [ + -25.005524619681388, + 131.0245292085271 + ], + [ + -25.415640726825877, + 130.71870447418462 + ], + [ + -25.815233888991809, + 130.39733655918104 + ], + [ + -26.207858116246577, + 130.0712118076184 + ], + [ + -26.590977128919985, + 129.74023056722521 + ], + [ + -26.966405255309642, + 129.41002220928868 + ], + [ + -27.348357245000454, + 129.07784654462935 + ], + [ + -27.73115519222273, + 128.74108153655033 + ], + [ + -28.106169687105886, + 128.39517112739495 + ], + [ + -28.472191840286989, + 128.04387319887624 + ], + [ + -28.835140987878304, + 127.68707063120357 + ], + [ + -29.180794724191959, + 127.32512842366485 + ], + [ + -29.517202926762536, + 126.94307930124508 + ], + [ + -29.849146005312157, + 126.56583241648075 + ], + [ + -30.18495509056012, + 126.19401898647288 + ], + [ + -30.531548114049851, + 125.81901332172295 + ], + [ + -30.87116440281844, + 125.45057135366061 + ], + [ + -31.2054178002536, + 125.06668063450422 + ], + [ + -31.529505047963877, + 124.6810317010352 + ], + [ + -31.838275498102167, + 124.2747395042079 + ], + [ + -32.116317829259948, + 123.85852046282926 + ], + [ + -32.361665156485564, + 123.41549804162477 + ], + [ + -32.566111850732689, + 122.95873076400194 + ], + [ + -32.723514160321066, + 122.48064879460648 + ], + [ + -32.83680227109658, + 121.99018014664047 + ], + [ + -32.899178485567461, + 121.48950546204667 + ], + [ + -32.910374980063338, + 120.97683133978043 + ], + [ + -32.888038091157213, + 120.47472275196756 + ], + [ + -32.8205252290246, + 119.97679634908445 + ], + [ + -32.704026236274011, + 119.47690172381917 + ], + [ + -32.573770256338172, + 118.99332899771154 + ], + [ + -32.429993676585276, + 118.51238685580286 + ], + [ + -32.2878348649037, + 118.02143264565994 + ], + [ + -32.1496646194766, + 117.52510535553716 + ], + [ + -32.000347477079465, + 117.04702713819565 + ], + [ + -31.837858966371186, + 116.56169778281598 + ], + [ + -31.680798843344963, + 116.08269082599303 + ], + [ + -31.529703335731167, + 115.59487058136816 + ], + [ + -31.376991168322387, + 115.10315793267237 + ], + [ + -31.219143051448096, + 114.62709633009018 + ], + [ + -31.053489354481261, + 114.1515142620467 + ], + [ + -30.8922817554455, + 113.67339637979686 + ], + [ + -30.732388860644498, + 113.19663424062325 + ], + [ + -30.571961670454652, + 112.72185758763428 + ], + [ + -30.414738449037216, + 112.24138194585035 + ], + [ + -30.255948792741705, + 111.75358311828416 + ], + [ + -30.09004267784702, + 111.27938444732993 + ], + [ + -29.912820726913161, + 110.80902276674662 + ], + [ + -29.729226474482168, + 110.34349960335396 + ], + [ + -29.538280527349453, + 109.87741567920882 + ], + [ + -29.341120850988212, + 109.40962636678458 + ], + [ + -29.137932909743405, + 108.94281482991467 + ], + [ + -28.928934008053254, + 108.47964852570412 + ], + [ + -28.727962408238653, + 108.01341841664326 + ], + [ + -28.525057822551613, + 107.54349485489827 + ], + [ + -28.307184415780959, + 107.07592373004097 + ], + [ + -28.076980820232798, + 106.61573525130596 + ], + [ + -27.842851940058992, + 106.16306989290582 + ], + [ + -27.604337594661562, + 105.71101364301215 + ], + [ + -27.366572548150476, + 105.25944009145242 + ], + [ + -27.128300317524488, + 104.81001710012306 + ], + [ + -26.885676836886855, + 104.36212101675775 + ], + [ + -26.64281040853054, + 103.91571825916567 + ], + [ + -26.400797750658157, + 103.46895308479724 + ], + [ + -26.151130416427996, + 103.02644996679234 + ], + [ + -25.886949532791391, + 102.59047324066876 + ], + [ + -25.619326252211426, + 102.15660534787855 + ], + [ + -25.348559217149365, + 101.72678652542498 + ], + [ + -25.077853238826663, + 101.30166857381477 + ], + [ + -24.799968006900624, + 100.86879502284513 + ], + [ + -24.523847879381922, + 100.44107861381563 + ], + [ + -24.2541864126172, + 100.01345842557288 + ], + [ + -23.9896254927232, + 99.586035250120929 + ], + [ + -23.723911754079115, + 99.145364655309621 + ], + [ + -23.464967238111775, + 98.707911054670944 + ], + [ + -23.210679973970862, + 98.269942358465386 + ], + [ + -22.960630931845962, + 97.832329904544252 + ], + [ + -22.718156435652919, + 97.394340350774286 + ], + [ + -22.480118726761887, + 96.9468216930209 + ], + [ + -22.239798864550455, + 96.497244554772763 + ], + [ + -22.019362222554129, + 96.042955963853956 + ], + [ + -21.819302578954854, + 95.582023431271878 + ], + [ + -21.631334721339716, + 95.1103678691315 + ], + [ + -21.465924934830653, + 94.624135335509507 + ], + [ + -21.328693975241904, + 94.129185689820133 + ], + [ + -21.20648252371166, + 93.634334350105249 + ], + [ + -21.0965590459394, + 93.136221308052114 + ], + [ + -20.999857805020238, + 92.642648097571239 + ], + [ + -20.914553378536404, + 92.148946519237285 + ], + [ + -20.830224155283208, + 91.639165485079744 + ], + [ + -20.7426454702118, + 91.130225303759033 + ], + [ + -20.655713119448482, + 90.625846809566738 + ], + [ + -20.572318495196612, + 90.127339361455455 + ], + [ + -20.484143888004649, + 89.619661470036675 + ], + [ + -20.3962386751971, + 89.121716515904367 + ], + [ + -20.307843870333262, + 88.615151296438768 + ], + [ + -20.221802187580852, + 88.118410671462541 + ], + [ + -20.130402590365989, + 87.615951558669323 + ], + [ + -20.035210348431185, + 87.124841565508021 + ], + [ + -19.939508164777656, + 86.626396133134023 + ], + [ + -19.840806589640419, + 86.119293697003314 + ], + [ + -19.742689371379448, + 85.627230159243538 + ], + [ + -19.6376535281886, + 85.128902512681975 + ], + [ + -19.527953390028543, + 84.62475292669248 + ], + [ + -19.417492528178578, + 84.136715807402 + ], + [ + -19.302151324454947, + 83.6447769845069 + ], + [ + -19.182973777570389, + 83.153396549675719 + ], + [ + -19.056751160625744, + 82.648522231261 + ], + [ + -18.928339690770443, + 82.152815787479511 + ], + [ + -18.796044817385155, + 81.663163770619875 + ], + [ + -18.659558792017034, + 81.176951784017021 + ], + [ + -18.520930876502089, + 80.692153397242066 + ], + [ + -18.377346188353513, + 80.212404327436587 + ], + [ + -18.227747329918206, + 79.717004930033866 + ], + [ + -18.08289597393507, + 79.223383613822477 + ], + [ + -17.942721714198964, + 78.731708065296516 + ], + [ + -17.801195948519887, + 78.2425036071391 + ], + [ + -17.657822194606595, + 77.757813705312756 + ], + [ + -17.510255792934892, + 77.275805250872239 + ], + [ + -17.353317973239047, + 76.782458343999537 + ], + [ + -17.200503585727759, + 76.289187390339393 + ], + [ + -17.054705470793788, + 75.799163423358792 + ], + [ + -16.91149133837764, + 75.313327871875 + ], + [ + -16.768352508341088, + 74.831076769512521 + ], + [ + -16.621674291448972, + 74.334480787102521 + ], + [ + -16.474494374535524, + 73.8419900740536 + ], + [ + -16.322441354183059, + 73.354250660726379 + ], + [ + -16.170334493813861, + 72.87043811783 + ], + [ + -16.020719730578428, + 72.389420543086814 + ], + [ + -15.869645751340276, + 71.912142844327221 + ], + [ + -15.71429530681789, + 71.424995351266688 + ], + [ + -15.563683158638959, + 70.941402206892619 + ], + [ + -15.41737950219972, + 70.4607429164928 + ], + [ + -15.2706192696264, + 69.9660595598522 + ], + [ + -15.13206895919892, + 69.473522282840165 + ], + [ + -14.994516031324045, + 68.983437606352211 + ], + [ + -14.849570043840393, + 68.498818321558446 + ], + [ + -14.692648770177151, + 68.021712075936819 + ], + [ + -14.520364819074533, + 67.536389613092055 + ], + [ + -14.338757260904904, + 67.061209305125928 + ], + [ + -14.142889680358456, + 66.59817685252446 + ], + [ + -13.917520767566822, + 66.13561127451635 + ], + [ + -13.670586378777719, + 65.689564205780712 + ], + [ + -13.403639581779459, + 65.263203756305117 + ], + [ + -13.109055927401478, + 64.84335343438363 + ], + [ + -12.790533494814511, + 64.446527776117861 + ], + [ + -12.446787017494687, + 64.0789477497395 + ], + [ + -12.072963640685979, + 63.729876197617244 + ], + [ + -11.691659858655337, + 63.405157479274052 + ], + [ + -11.280319172843942, + 63.10119404506915 + ], + [ + -10.847504277297345, + 62.836778514262434 + ], + [ + -10.397596902874973, + 62.588934827395867 + ], + [ + -9.9407990301906537, + 62.356254847216839 + ], + [ + -9.4865791159407422, + 62.142373750800076 + ], + [ + -9.0254494332883013, + 61.937789517174984 + ], + [ + -8.5595885454087153, + 61.736204278929911 + ], + [ + -8.0843183480844818, + 61.544554704153562 + ], + [ + -7.6010325430896177, + 61.367541519536822 + ], + [ + -7.128075702790186, + 61.200301052882246 + ], + [ + -6.6553686916711943, + 61.024846055023751 + ], + [ + -6.1788633960998895, + 60.846096619571682 + ], + [ + -5.6997786219492133, + 60.671735339038072 + ], + [ + -5.21932926580529, + 60.491166602403922 + ], + [ + -4.73767836207931, + 60.3126342412852 + ], + [ + -4.2530240217831965, + 60.139344486742814 + ], + [ + -3.7666528574388214, + 59.970892543070512 + ], + [ + -3.2822183485906788, + 59.811632645107544 + ], + [ + -2.8020320632037845, + 59.657748066024034 + ], + [ + -2.3211518618694194, + 59.5103240591197 + ], + [ + -1.839090029752068, + 59.370664713943185 + ], + [ + -1.3548407320627531, + 59.23690020283577 + ], + [ + -0.86327443259970937, + 59.109760209215978 + ], + [ + -0.3642478003963347, + 58.990538403014888 + ], + [ + 0.13608932685219716, + 58.8786998695715 + ], + [ + 0.6321454178591962, + 58.77475320702132 + ], + [ + 1.1251143823465875, + 58.666784376548257 + ], + [ + 1.6161099111951247, + 58.5563208005173 + ], + [ + 2.1205963685905509, + 58.454119128747465 + ], + [ + 2.6217709282953412, + 58.349834844963631 + ], + [ + 3.1178811418670063, + 58.240575945755921 + ], + [ + 3.611280873269032, + 58.144486990626334 + ], + [ + 4.1160941663932782, + 58.056684277640748 + ], + [ + 4.618763716078063, + 57.977336755906848 + ], + [ + 5.1186230858781725, + 57.907870818535926 + ], + [ + 5.6236894186934734, + 57.83863230473515 + ], + [ + 6.1319151072678038, + 57.764047186078962 + ], + [ + 6.6350378783894888, + 57.701698111672108 + ], + [ + 7.1338467662170206, + 57.6460961897819 + ], + [ + 7.6432891027590379, + 57.583003273757818 + ], + [ + 8.1493049692632127, + 57.522307397718542 + ], + [ + 8.6506133103368441, + 57.45666954167239 + ], + [ + 9.1477084203969721, + 57.3849573453051 + ], + [ + 9.6437239296867521, + 57.311999671516844 + ], + [ + 10.140328656578751, + 57.236803810533935 + ], + [ + 10.635917443045466, + 57.163471703284323 + ], + [ + 11.142125362947061, + 57.101199248506582 + ], + [ + 11.645771359215834, + 57.041296870262293 + ], + [ + 12.147399284213584, + 56.976265780453339 + ], + [ + 12.655273892566031, + 56.907709223061076 + ], + [ + 13.152619729981611, + 56.82594871340347 + ], + [ + 13.653375613523444, + 56.723038781213958 + ], + [ + 14.146457843348825, + 56.611069038253142 + ], + [ + 14.644739951599039, + 56.49342280707431 + ], + [ + 15.133737648969966, + 56.37418657024169 + ], + [ + 15.627092893450142, + 56.258171222622259 + ], + [ + 16.115434101817257, + 56.135884337434256 + ], + [ + 16.604660009099916, + 56.023677360137022 + ], + [ + 17.092059161053328, + 55.906504311059024 + ], + [ + 17.578291484088794, + 55.779576560923275 + ], + [ + 18.067576499840662, + 55.6578663081453 + ], + [ + 18.558288149229821, + 55.556222825917565 + ], + [ + 19.043246208405762, + 55.429902864321086 + ] + ], + "Centre":[[18.892230073056275, +58.833089272301741], +[19.37483773162938, +58.703980573695894], +[19.854221945569538, +58.563132438704294], +[20.330420582899858, +58.411786277350586], +[20.803586015848747, +58.25117692890224], +[21.273957036027369, +58.082495759592589], +[21.741850241313116, +57.9069177136653], +[22.20763720387146, +57.725595272076617], +[22.671717433654038, +57.539688142350386], +[23.134505500528778, +57.350355377746816], +[23.596430784943795, +57.158749254070088], +[24.057941564370942, +56.9660064126077], +[24.519497274163381, +56.773256100123731], +[24.98149708831366, +56.581476834413174], +[25.444088761224709, +56.391045673523919], +[25.90735380995109, +56.202185840497073], +[26.371377134201392, +56.015118739492074], +[26.836267011117592, +55.830060309176851], +[27.302135117844369, +55.647226638448217], +[27.769105974144143, +55.466907300784911], +[28.237363099198745, +55.289679319548], +[28.707095414578355, +55.116198681154415], +[29.178476866201414, +54.947127438708591], +[29.651659484429953, +54.783119579046669], +[30.126779310368871, +54.624836296373061], +[30.603939556068088, +54.47288551855943], +[31.083169599303229, +54.327658630268694], +[31.564465216191056, +54.189496944004112], +[32.047800773843306, +54.058746759058316], +[32.533134023529364, +53.935753992260423], +[33.020415855001481, +53.820864862366335], +[33.5095613603972, +53.714302075016079], +[34.0003731615324, +53.615809450240981], +[34.49263925724307, +53.525008770110986], +[34.9861630523101, +53.441516190103705], +[35.480759161858344, +53.36493492173885], +[35.9762414907133, +53.294860400740873], +[36.472404391248915, +53.230638532309129], +[36.969006856355605, +53.170670710263053], +[37.465855004170706, +53.113120364200654], +[37.962788822795325, +53.056174320164587], +[38.45964117577131, +52.99811597848273], +[38.956225071722976, +52.937259748162127], +[39.452358120920479, +52.872275632213857], +[39.947992808910726, +52.803148380310809], +[40.443134739449178, +52.730186729728771], +[40.9378019677798, +52.65367870227707], +[41.432009560321276, +52.573841813214145], +[41.925769210142974, +52.490874953054956], +[42.419074335724048, +52.404877739575717], +[42.911854415707246, +52.315586701422127], +[43.404021139189368, +52.222650788376143], +[43.895485108541706, +52.125807011179923], +[44.386157350877383, +52.025112220489191], +[44.875944281359139, +51.9207217578775], +[45.36489119369088, +51.813326899140371], +[45.853589516565869, +51.7054811053976], +[46.342781013694236, +51.600186685620088], +[46.833135840100255, +51.500339046369419], +[47.325151334745868, +51.408479842141162], +[47.819167479199962, +51.327086264416629], +[48.31530831487914, +51.258583617346659], +[48.81340187473905, +51.205190967246125], +[49.313083399112138, +51.169068876866071], +[49.813808889007191, +51.15222455095082], +[50.314849111369291, +51.156028542430434], +[50.815300519903673, +51.181728685508759], +[51.314135890212945, +51.22992579580783], +[51.810525209580049, +51.299088351477963], +[52.303921490641677, +51.387167004097272], +[52.793984380074995, +51.492269483531963], +[53.280472054123294, +51.612912591364164], +[53.763229922548277, +51.7477037139796], +[54.242218841529912, +51.895201849921051], +[54.717637097725493, +52.053704933557796], +[55.189858692228057, +52.221510532319421], +[55.659316938372406, +52.397070384341461], +[56.126304798942748, +52.579209730433945], +[56.591102458555248, +52.766860334275094], +[57.05394492190328, +52.959175709218158], +[57.514823665784569, +53.155998616245981], +[57.973661968992538, +53.357334900922091], +[58.43040280135353, +53.563145112753283], +[58.885075990785786, +53.773257523908796], +[59.337738902478755, +53.987471395830333], +[59.788455960100876, +54.205581317130871], +[60.237300027165148, +54.42735895967553], +[60.684349839419511, +54.652572743195286], +[61.129686048952436, +54.88100233627717], +[61.573383748577037, +55.112456349488056], +[62.015517605448977, +55.346752615474223], +[62.456153433950945, +55.583730374165725], +[62.89532586276556, +55.823292026747808], +[63.333066274272184, +56.065355359376809], +[63.769427056877319, +56.309805058330809], +[64.204517179391686, +56.556418294523084], +[64.6384628849244, +56.804945613406176], +[65.071409756538912, +57.05510931271975], +[65.50355629779385, +57.30654058866515], +[65.935115199103308, +57.558848711849826], +[66.366304992016055, +57.811638847656496], +[66.797359841901027, +58.064501545024612], +[67.228519412786412, +58.317023218616939], +[67.660039916472073, +58.568768693459916], +[68.0922273418019, +58.819233639728544], +[68.525393493934345, +59.067895921219204], +[68.959820040644132, +59.314262237492649], +[69.395713679176509, +59.557940460291249], +[69.833257902962416, +59.79856285307865], +[70.272615649400223, +60.035788625454728], +[70.713898516882892, +60.26936897547823], +[71.157200024171743, +60.499074317425624], +[71.602607919552668, +60.724666656740936], +[72.0502103160465, +60.945889821793116], +[72.500092893975363, +61.162480579683823], +[72.9523502430763, +61.37415190422859], +[73.4071110364664, +61.580541211893916], +[73.864490976239068, +61.78126142593306], +[74.324536919352155, +61.976011763229678], +[74.787138701171315, +62.16481575363612], +[75.252157016584889, +62.34778414260699], +[75.719432673810218, +62.525101045207364], +[76.188723300690967, +62.6971884059925], +[76.6597831634004, +62.864536819819222], +[77.132363934296748, +63.027688519044041], +[77.606156162900035, +63.187342845474774], +[78.080847137087432, +63.344243491647042], +[78.5561447502482, +63.499167885619713], +[79.031793934713576, +63.652994384905163], +[79.507551840145183, +63.8066332084852], +[79.983105557111813, +63.961116876092866], +[80.457898396158413, +64.11788810939376], +[80.931300220836548, +64.278488769978466], +[81.402680798884177, +64.444594636040108], +[81.871418955822179, +64.61835983526467], +[82.336735951522357, +64.802011950084861], +[82.797675403643183, +64.997475940645714], +[83.253326602588857, +65.205878201565056], +[83.702777710689446, +65.428136362213863], +[84.14504203462873, +65.665072107067445], +[84.578997628799783, +65.917257735103632], +[85.003497234316328, +66.185182705513739], +[85.417488308988311, +66.469184227111541], +[85.820197997425069, +66.769151286592091], +[86.210865595394012, +67.084823233219069], +[86.588706063547974, +67.41585396238861], +[86.953029735246858, +67.761767441855369], +[87.303178755867776, +68.12205594891482], +[87.638506314789, +68.4962081805799], +[87.958427530880826, +68.88368413325901], +[88.262345148042527, +69.283926947201508], +[88.549687016407162, +69.6962966405764], +[88.819970118315339, +70.120018906943869], +[89.072770388104615, +70.554332677138717], +[89.307464981686337, +70.998639060982541], +[89.522606087212267, +71.452690236101489], +[89.716511169209923, +71.9161311962927], +[89.8873376407164, +72.3884632307359], +[90.033085916882683, +72.869092909735315], +[90.151611140997232, +73.357132999897175], +[90.242279438342024, +73.8510414063441], +[90.309210834721057, +74.3486373032743], +[90.357712908960451, +74.848364921478279], +[90.392899931788349, +75.349301691116665], +[90.419259635264524, +75.85084622481763], +[90.441074847050132, +76.352611924986007], +[90.460978324031174, +76.854392720285134], +[90.477120108850443, +77.356204591224483], +[90.4865966425046, +77.858055273964453], +[90.486778906836534, +78.359840756276739], +[90.475794499572771, +78.861370568066121], +[90.451984479038032, +79.362351834950914], +[90.41423420125362, +79.862397515596669], +[90.362728012653037, +80.361127811969453], +[90.297966478399644, +80.8582139712056], +[90.220401984299869, +81.35337298838931], +[90.130368076286544, +81.84635933092288], +[90.028182489360972, +82.336941342130132], +[89.914250687112386, +82.8249138507104], +[89.789214966371574, +83.310150871504675], +[89.653754896075725, +83.7925907295508], +[89.508516889370455, +84.272209530188434], +[89.354103212024214, +84.748990064368769], +[89.191105330628375, +85.222932315578561], +[89.02014909005112, +85.6940738398663], +[88.841949108546459, +86.162523260027839], +[88.657213560629614, +86.628437135845431], +[88.466512523768728, +87.091948860710218], +[88.270119098425809, +87.553067670239], +[88.068219518030944, +88.011769189643772], +[87.860837572690812, +88.46797126896341], +[87.64763121471141, +88.921440985055341], +[87.428199441959279, +89.371893898965652], +[87.202305087917182, +89.819099666279413], +[86.970058797489287, +90.263004102103821], +[86.73166052373108, +90.703609268539822], +[86.487422792014641, +91.140982425309417], +[86.237908260284783, +91.575334725212542], +[85.983709589320554, +92.006926756850078], +[85.7252700999301, +92.435957862380221], +[85.462729113370841, +92.862450581732389], +[85.196145500570452, +93.286378723388566], +[84.925489646606763, +93.707668139456388], +[84.650544118859486, +94.1261351490533], +[84.371070809757825, +94.541563006750692], +[84.086956106443608, +94.9537958043906], +[83.798331510635677, +95.362843903418877], +[83.505383302893847, +95.768769333404776], +[83.208328639665922, +96.171665434430281], +[82.907456847534, +96.571682228354092], +[82.603071934486067, +96.968997325640316], +[82.2955094669392, +97.363828766767838], +[81.985184515599229, +97.756465518980832], +[81.672532994081649, +98.1472224405673], +[81.358032513099218, +98.536459500708077], +[81.042253473405751, +98.924625637549241], +[80.725765269818979, +99.312178595457965], +[80.408982012729808, +99.699453753968555], +[80.091998255288729, +100.08652566464109], +[79.774825839566233, +100.47340121558902], +[79.457414807219649, +100.86003732608589], +[79.139586984191823, +101.24628680288806], +[78.821145072296929, +101.63198622586739], +[78.501973155841014, +102.01703970255642], +[78.182122603191232, +102.40149268436494], +[77.86168608199651, +102.78542643125158], +[77.540775517442412, +103.168940191422], +[77.219543037272615, +103.55217009074504], +[76.898147736843583, +103.93525932399727], +[76.5767319667229, +104.31833636720091], +[76.255403810976546, +104.70149891436087], +[75.93426387657577, +105.08483762650079], +[75.613416787269742, +105.46844473977396], +[75.292975555413591, +105.85241556929444], +[74.973051227432578, +106.23684159261884], +[74.6537204176563, +106.62178341453762], +[74.334987311779528, +107.00723967430022], +[74.016839127778724, +107.39319553783973], +[73.69926648755731, +107.77964018741029], +[73.382267714124083, +108.16657027367573], +[73.06582928834672, +108.55397279867482], +[72.749831537524585, +108.94174826640659], +[72.4339368970676, +109.32962060286052], +[72.1177511922835, +109.71726869460478], +[71.800840122985761, +110.10433949854445], +[71.4826886629046, +110.49041346917258], +[71.162782948194916, +110.87506272194958], +[70.840735694466446, +111.25794924685619], +[70.516407538973155, +111.63892886939198], +[70.189719388587832, +112.0179055114863], +[69.860613068566551, +112.39480046388647], +[69.529072342964611, +112.76957002288293], +[69.195092137541025, +113.14217859701465], +[68.858673041893127, +113.51259426090046], +[68.519825840506314, +113.88079371574378], +[68.178563556870714, +114.24675585852459], +[67.834899615243472, +114.61045883753604], +[67.4888485762488, +114.97187900134978], +[67.1404291692539, +115.33099609055066], +[66.7896888207155, +115.68781804022083], +[66.436731343562926, +116.04240935971114], +[66.081672203751751, +116.39484953761658], +[65.724625331480908, +116.74522142128205], +[65.365703549845875, +117.09361240858911], +[65.005024073914583, +117.44011747918958], +[64.642742796927877, +117.78487545696298], +[64.2790920756552, +118.12811174548077], +[63.914320081555545, +118.47007539643396], +[63.54868012880047, +118.81102445080967], +[63.182439523813791, +119.15123130317579], +[62.815869408492674, +119.49097479249704], +[62.449251785537648, +119.8305519519197], +[62.082891783229122, +120.17029457323164], +[61.717101440672543, +120.5105422536555], +[61.35220206822909, +120.85163699164745], +[60.988532488515027, +121.193926762214], +[60.626435423000906, +121.53775704514287], +[60.266241782945045, +121.88345746612552], +[59.908257532022454, +122.23132804663946], +[59.552787468452564, +122.5816548588127], +[59.200136875913017, +122.93470543474049], +[58.850603913221917, +123.29071906976722], +[58.50449423272007, +123.6499297253317], +[58.162163725415269, +124.01260488542351], +[57.824073315797015, +124.37908777224278], +[57.490721847048732, +124.74973178506767], +[57.162653561028378, +125.12491797804479], +[56.840500655528928, +125.50509742320281], +[56.524926740691456, +125.89068870443873], +[56.216464391760532, +126.28193420957912], +[55.91529304852552, +126.67876049702159], +[55.6214930224509, +127.08102461684203], +[55.335068050381338, +127.48852839411749], +[55.055856065432486, +127.90094452810315], +[54.783651226402448, +128.31794257269638], +[54.518351332417936, +128.7392876792627], +[54.26013456164732, +129.16492624207211], +[54.009257406413809, +129.59483884289483], +[53.766035716853395, +130.0290337439375], +[53.530922452016178, +130.46760000371719], +[53.3044132891925, +130.91061707025838], +[53.086940727826253, +131.3580921333153], +[52.878736726344926, +131.80991215316274], +[52.679981331056588, +132.26593619764128], +[52.490814575127885, +132.72600199781962], +[52.311269603180449, +133.18989435816482], +[52.141352263545564, +133.65738938046317], +[51.981096545660854, +134.12827734986084], +[51.83062301073911, +134.60237752829735], +[51.690075601925429, +135.07951142309108], +[51.559615340902894, +135.55949637889771], +[51.439450577479157, +136.04214743704668], +[51.3298025839622, +136.527273732608], +[51.230883746343707, +137.0146743741947], +[51.14288268659385, +137.50413335324538], +[51.06598205049908, +137.99542382930716], +[51.000376937524, +138.48831382421608], +[50.946307897524129, +138.98257394650386], +[50.904027811286809, +139.47795979957112], +[50.873750793360756, +139.97420646009857], +[50.855522013985819, +140.4710341575273], +[50.849350318668428, +140.968160054934], +[50.855149682493135, +141.46529754182006], +[50.8725175187974, +141.96216865426496], +[50.900811628484334, +142.45854069810821], +[50.939550841411929, +142.95421457960845], +[50.988565051821269, +143.44898384596587], +[51.047768409343107, +143.94263979391565], +[51.117257573493838, +144.43495353114488], +[51.197863585162686, +144.9255725349386], +[51.290609895647577, +145.41404702890981], +[51.396430213827685, +145.89987038120807], +[51.515969927645813, +146.38255033088709], +[51.649775063494893, +146.86154931857948], +[51.798188259755065, +147.3363086467852], +[51.960773261141284, +147.80647881960411], +[52.136875927327978, +148.27183854911073], +[52.325883007835472, +148.73220360092816], +[52.527287752382009, +149.187333684385], +[52.740634823989282, +149.63699801503122], +[52.965539230050524, +150.08099136038572], +[53.201849356245226, +150.51904568010659], +[53.449477385619041, +150.95083923794135], +[53.708312555175453, +151.37602210054578], +[53.978222923163145, +151.79425408725993], +[54.2590725201827, +152.20522091746602], +[54.550615097736824, +152.60870784220242], +[54.852118587964981, +153.00486559036943], +[55.162674996405016, +153.39402029223589], +[55.481391323926715, +153.776552935905], +[55.807408308310663, +154.15291474622202], +[56.139906705843842, +154.52360605702336], +[56.478230044036167, +154.8890398164844], +[56.822288296446644, +155.24912072079508], +[57.172223497539633, +155.60352494933278], +[57.528208694368708, +155.95188746584208], +[57.890468513242809, +156.29378411026448], +[58.259228009917095, +156.62874751754944], +[58.634603946136849, +156.95637086854148], +[59.016358725099792, +157.27663306917745], +[59.404114490713482, +157.58971355522124], +[59.797485823260274, +157.89584404544649], +[60.196043347119655, +158.19532318783456], +[60.599352769753267, +158.48849052554397], +[61.007027059332877, +158.77566995006566], +[61.418811089727825, +159.05703097711975], +[61.834511178855649, +159.33266652863969], +[62.253954083468088, +159.60265379255506], +[62.677014215571013, +159.86703536426083], +[63.103584286926093, +160.1258343270658], +[63.533534346675424, +160.3791016306549], +[63.966653490146761, +160.62703809107728], +[64.402702867914513, +160.86993089451329], +[64.8414491400966, +161.10809296082257], +[65.282644389306029, +161.34186922211836], +[65.72603847339866, +161.57162440426649], +[66.171386680668718, +161.79774053013082], +[66.618435938597329, +162.02064139912295], +[67.0669314134588, +162.24077537261428], +[67.516622637636189, +162.45860355823794], +[67.967259803104739, +162.6746159171943], +[68.418596116948521, +162.88931958259187], +[68.870389987846835, +163.1032216675672], +[69.322406476251459, +163.31681087670583], +[69.774413500398751, +163.53056584049432], +[70.2261762725815, +163.744971660653], +[70.67744728967493, +163.96054704762383], +[71.127968116220913, +164.17782716875547], +[71.57749353995041, +164.39729970983987], +[72.025867839716966, +164.61924690674675], +[72.472983927253935, +164.84384038417775], +[72.918749740222438, +165.07121238371306], +[73.363115964669561, +165.30139579697033], +[73.80605928935671, +165.53437176761508], +[74.24755270092372, +165.77013570267789], +[74.687523747914739, +166.00877018799258], +[75.125872133738341, +166.25040249273985], +[75.562484686589428, +166.49517482124773], +[75.997221433436977, +166.743274581879], +[76.429924331852874, +166.99491083555043], +[76.860443408992, +167.25026257324438], +[77.288698417297809, +167.50937959002837], +[77.714648280533225, +167.77224524767092], +[78.13826478912236, +168.03882618809638], +[78.55954653350949, +168.30905317726831], +[78.978505558647413, +168.58283827770259], +[79.395164261917984, +168.86007851189675], +[79.809583634967339, +169.14061910412514], +[80.221848456931269, +169.42428085130692], +[80.632054027629437, +169.71087954302448], +[81.040311693539138, +170.00021292271353], +[81.446742147525555, +170.29207011628057], +[81.851480224140786, +170.58622719247376], +[82.254709198577928, +170.88240442289276], +[82.6566398947457, +171.18029554310033], +[83.0575002756774, +171.4795807503269], +[83.457564317950016, +171.77988839706768], +[83.857130936581612, +172.08082173070915], +[84.256475379144547, +172.38201832125736], +[84.65575085169057, +172.68327274542906], +[85.055048544328386, +172.98445886445325], +[85.45444143856021, +173.28547489652087], +[85.853960428100493, +173.58627781011685], +[86.253615167617625, +173.88685422300716], +[86.653416425134836, +174.18718980319395], +[87.053392002762948, +174.48724905085797], +[87.4535782220858, +174.7869857654191], +[87.854013838679364, +175.08635077371605], +[88.25474339782609, +175.38528845586598], +[88.655814220403172, +175.68373984006593], +[89.057265118983281, +175.98165700165887], +[89.4590976473996, +176.27904194178967], +[89.861294713058285, +176.575921904178], +[90.263831193886773, +176.87233461853026], +[90.666658010348115, +177.1683481235668], +[91.069714202482089, +177.46404590572806], +[91.472952774770647, +177.75949253066167], +[91.876392690343039, +178.05466185462251], +[92.280086123453685, +178.34948177974474], +[92.684097609962535, +178.64386326983794], +[93.0885258328417, +178.937671409379], +[93.493486036690911, +179.23074750670779], +[93.899073981931792, +179.52295664180207], +[94.305296792412435, +179.81428314126487], +[94.712117390543085, +180.10477241926571], +[95.119485452601708, +180.39448920339191], +[95.527317460711458, +180.68354420736011], +[95.935513409859382, +180.97207178774732], +[96.343982154757711, +181.26019479417857], +[96.752678351435719, +181.54797153983358], +[97.161579889808422, +181.83542740952223], +[97.5706704029368, +182.1225796647189], +[97.979944650298236, +182.4094298980138], +[98.389403089513053, +182.69597172583119], +[98.799047373344337, +182.98219815384368], +[99.208880838533588, +183.26810411895048], +[99.61890761906146, +183.55368549691133], +[100.02912726369181, +183.83894372191139], +[100.43951954052447, +184.1239038626137], +[100.85005421066874, +184.40860325981106], +[101.26072550503531, +184.69304469296355], +[101.67163830981566, +184.977074724505], +[102.08295424961796, +185.26045880878561], +[102.49485198774244, +185.54293594242245], +[102.90755269873291, +185.82418119788474], +[103.32129774866965, +186.10383502838351], +[103.73632654873086, +186.38153129709008], +[104.15286832441316, +186.65690368286994], +[104.5711442506, +186.9295837731359], +[104.99137840928984, +187.19919017592039], +[105.41382643067308, +187.46529427189009], +[105.83875051173736, +187.72743526010808], +[106.26636716013277, +187.98518308476318], +[106.69675195388274, +188.23830025002368], +[107.12991012973524, +188.48665632195579], +[107.56583060776323, +188.73015240727432], +[108.00446584294387, +188.96875555033], +[108.44574783774985, +189.20246769054211], +[108.88959113512394, +189.43132368772086], +[109.33585305742652, +189.65548101424358], +[109.78436536335457, +189.87516850861186], +[110.23495605405908, +190.09064493995368], +[110.6874277493894, +190.3022428206103], +[111.14157479818921, +190.51033872482088], +[111.59719699346095, +190.71532353601577], +[112.05409154308778, +190.91760719808852], +[112.5120558776528, +191.11761164616945], +[112.97088878326925, +191.31576992145037], +[113.43037979342718, +191.51254809994003], +[113.89031440107432, +191.70843182601777], +[114.3504843396822, +191.9039002840872], +[114.81070331251988, +192.09938720202291], +[115.2707967749763, +192.29530031426239], +[115.73059314144712, +192.49203965594137], +[116.18992850654668, +192.68998882450651], +[116.64864099339115, +192.88952125947276], +[117.10656346762669, +193.09100752626918], +[117.56351843691039, +193.29481663084795], +[118.01932033254113, +193.50131603284504], +[118.4737736200604, +193.71088256362154], +[118.92665645084622, +193.92394112832605], +[119.37772388805163, +194.14094014669271], +[119.82674595459682, +194.36226156372678], +[120.27362251238489, +194.58800520281957], +[120.71833141769, +194.81811516922653], +[121.16088251973522, +195.05247468282658], +[121.60137200706922, +195.29079546302887], +[122.03995345491924, +195.53269947376572], +[122.47676153946966, +195.77787193687385], +[122.91176638910167, +196.02630728060575], +[123.34484101769908, +196.27816565749146], +[123.77582619270146, +196.5336518598057], +[124.20450142068076, +196.79307423677184], +[124.63060592867046, +197.0567928385978], +[125.05387113693013, +197.32515020267778], +[125.47406195746224, +197.59840324743195], +[125.8909586635699, +197.8767626321409], +[126.3043395373461, +198.16042412877613], +[126.71398555217021, +198.44955935893432], +[127.1196756307391, +198.74432552545881], +[127.52116807048135, +199.04488843416922], +[127.91815041780164, +199.35147108520979], +[128.31026525488255, +199.66431946102614], +[128.69714431329439, +199.98367374112519], +[129.07843673081027, +200.30976795138275], +[129.45378492408256, +200.64282388901125], +[129.82273783062732, +200.9830997840032], +[130.18452272089979, +201.33106237337887], +[130.53818960303929, +201.68726221941719], +[130.88275546720303, +202.05224795705027], +[131.21724403344675, +202.42661444061474], +[131.54059797499556, +202.81090977244759], +[131.85166197965208, +203.20552459822994], +[132.14934094646091, +203.61058173364813], +[132.43256789283413, +204.02610458825637], +[132.70026013259974, +204.45204148910946], +[132.95125038294276, +204.88812962029317], +[133.1843428371476, +205.33398955700247], +[133.39853538003268, +205.78914135918791], +[133.59366285720276, +206.25280388565471], +[133.76989572839034, +206.72405192076815], +[133.92739726091577, +207.20191694797319], +[134.06626756212222, +207.68545096744685], +[134.18661058379854, +208.1737979787338], +[134.28856143590625, +208.66620216514511], +[134.3722445264807, +209.16196145544734], +[134.43778154116825, +209.66035160585429], +[134.4852944211072, +210.1606327449106], +[134.51491541891542, +210.66214563292073], +[134.52677980543149, +211.16428220062505], +[134.52100574991456, +211.66644314865454], +[134.49765528506936, +212.16799941940357], +[134.45677182634267, +212.66832461508668], +[134.39841694838464, +213.16680765468649], +[134.32273254901105, +213.66284268956548], +[134.22989120487787, +214.15583105209382], +[134.12008034112523, +214.64519321919903], +[133.99354046023248, +215.13039819693034], +[133.85052990727519, +215.61092473759604], +[133.69134334240871, +216.0862550571311], +[133.51640728571425, +216.55592783674612], +[133.32618763687606, +217.01953398904209], +[133.1211649746096, +217.47671489562245], +[132.90191891622391, +217.92719847375741], +[132.66905889920574, +218.37075495008492], +[132.42321593873234, +218.80719544165143], +[132.16511196131574, +219.23644359384059], +[131.89548118511624, +219.65850712097341], +[131.61505831678875, +220.07346119457975], +[131.32468018799671, +220.48149333512887], +[131.02519365448359, +220.88287238244803], +[130.71738561722742, +221.27789998647583], +[130.40191428592269, +221.666823990531], +[130.07938386129842, +222.04989180402862], +[129.75036491017187, +222.42736862409026], +[129.41536651724715, +222.79951056490256], +[129.07487228496436, +223.16657913192267], +[128.72938503463698, +223.52888182466438], +[128.37951738160854, +223.88688221428782], +[128.02590283872181, +224.241115180808], +[127.66917815106487, +224.59215879192223], +[127.31005065194897, +224.94069070146173], +[126.94923909946883, +225.28743347436568], +[126.58734541439728, +225.63300656458333], +[126.2245310203314, +225.97755796841787], +[125.86081312257171, +226.32107795291941], +[125.49617209733117, +226.66351870843894], +[125.13047247887212, +227.0047204286669], +[124.76354320342918, +227.34448440106112], +[124.39529975779382, +227.68270141129318], +[124.02600537437415, +228.0196506787031], +[123.65603232638341, +228.35574274720824], +[123.2857664439733, +228.69141274992265], +[122.91563422040026, +229.02715244319907], +[122.54607666902238, +229.36347068750428], +[122.17751576305689, +229.7008439561757], +[121.81028197296278, +230.03962192590859], +[121.44467669068831, +230.38011135451538], +[121.08099956948709, +230.72261611624776], +[120.71954781998431, +231.06744402959387], +[120.36062677116593, +231.41489615416577], +[120.00453052161353, +231.76523331664538], +[119.65146007953584, +232.11859421899567], +[119.30158134826713, +232.47508073436387], +[118.95505721807338, +232.83479871375161], +[118.61206224424225, +233.19786939517331], +[118.27278245852284, +233.5644117395461], +[117.93731646513564, +233.93444795938191], +[117.60536540540556, +234.3076438808659], +[117.27648107814181, +234.68355761783306], +[116.95017936924967, +235.06173977457689], +[116.62591006464848, +235.44169570637629], +[116.30309534554478, +235.82292093517535], +[115.98126249565397, +236.20501054194909], +[115.66039848860351, +236.58794918335261], +[115.34065229283291, +236.97185569591767], +[115.02220128054041, +237.35686992715492], +[114.70528515402211, +237.7431808053899], +[114.39016792629479, +238.1309916231819], +[114.0770155727146, +238.52042030153763], +[113.76556868619575, +238.91124610326156], +[113.4554126537584, +239.30313357045074], +[113.14610331737848, +239.69573101035803], +[112.83713747514545, +240.08864211910711], +[112.52799071630862, +240.48145472301985], +[112.21822076544983, +240.87381734389191], +[111.90772662606648, +241.26563988431883], +[111.59652842628229, +241.65692699454928], +[111.2846610791744, +242.04769780151531], +[110.97218248727441, +242.437996551352], +[110.6591587253303, +242.82787658429498], +[110.34566669176169, +243.2174004422734], +[110.03182564378297, +243.60666493913683], +[109.71776989631219, +243.99577936525236], +[109.40364138227798, +244.3848583390664], +[109.08960885641386, +244.7740335826301], +[108.7758509412764, +245.16344266439867], +[108.46249285760112, +245.55317926895711], +[108.14943434875676, +245.94315700731866], +[107.83649388917466, +246.33322571286965], +[107.52347351279697, +246.72322374655491], +[107.21013557138127, +247.11296183892983], +[106.89622885975737, +247.50224007117754], +[106.58154044666628, +247.89088669950655], +[106.26601553180315, +248.27885446182668], +[105.94965529291132, +248.66614106994581], +[105.63246731038227, +249.05275012013897], +[105.3144682515231, +249.43869335995481], +[104.99567804036408, +249.82398540506608], +[104.67613688741835, +250.20865744442821], +[104.35596726677255, +250.59280820131298], +[104.03532047440804, +250.97656100796334], +[103.71435647947878, +251.36004669549067], +[103.39326303153129, +251.74341715744757], +[103.07223771704528, +252.12683180131091], +[102.75143261074268, +252.5104123657446], +[102.43080877266598, +252.89412385751703], +[102.11025931841741, +253.27787590358179], +[101.78966378424634, +253.66156758859748], +[101.46886816346741, +254.0450720231037], +[101.14770686670394, +254.428252772945], +[100.82604365145562, +254.81099675996461], +[100.50386470739096, +255.19329238316033], +[100.18119927487481, +255.57516443583717], +[99.858079354645071, +255.95664038432645], +[99.534535465647366, +256.3377457036529], +[99.2105978046867, +256.71850490536218], +[98.886341035129362, +257.09897997363157], +[98.562021700029234, +257.47938879908924], +[98.237960520985936, +257.86000509820383], +[97.9144963792186, +258.24111837547315], +[97.592022857392593, +258.62306430811356], +[97.2709569379686, +259.00619040170773], +[96.951636575614643, +259.39076392547861], +[96.6340422333632, +259.77674728340048], +[96.318022135468254, +260.16399967527815], +[96.003397060341214, +260.55236546554278], +[95.689930295430742, +260.94164678826542], +[95.377363468298611, +261.3316322030725], +[95.0654653656726, +261.72213518860394], +[94.754128709007347, +262.11307002817995], +[94.443290964995214, +262.50438686321758], +[94.132892632904273, +262.8960381871733], +[93.822870976520946, +263.28797502967529], +[93.5131617934759, +263.680148274088], +[93.203740196135243, +264.07254035811178], +[92.894744394282071, +264.46526290274977], +[92.586372016453339, +264.85847394436337], +[92.278835924396517, +265.25234277576249], +[91.972390100224658, +265.64707093539448], +[91.667306076098811, +266.04286853205213], +[91.363817513777732, +266.43990710169521], +[91.061981067166016, +266.83821452368215], +[90.761786349685352, +267.23776887041913], +[90.4632102230785, +267.63854191592969], +[90.1662062482772, +268.0404891630252], +[89.870719063100836, +268.4435606455246], +[89.5766898190498, +268.84770581650906], +[89.2840507020852, +269.25287075164744], +[88.992730411403983, +269.65900051423716], +[88.702656110253912, +270.06604043650373], +[88.41375086875864, +270.47393583179587], +[88.125936322620547, +270.88263190212507], +[87.839131824312375, +271.29207286417227], +[87.553247255714766, +271.70219961191879], +[87.268188269264527, +272.11295281109597], +[86.983860706345268, +272.5242740421109], +[86.70017516018099, +272.93610513505382], +[86.417043916805142, +273.34838806389678], +[86.134368024202985, +273.76105694601887], +[85.852001903752168, +274.17401286042394], +[85.569782283713877, +274.587144836838], +[85.287547060462984, +275.000341207032], +[85.00514624697756, +275.41349124320061], +[84.722434328199185, +275.82648449852911], +[84.43921931216876, +276.23917933962855], +[84.155115803135445, +276.65130462672613], +[83.869668525720087, +277.0625391211106], +[83.5824138888249, +277.47255390620711], +[83.292871527351025, +277.881017303966], +[83.000559969389627, +278.28758820343546], +[82.704976689590069, +278.69188269979048], +[82.405510094638487, +279.09338429534648], +[82.101515699074724, +279.49151894020531], +[81.792347331150324, +279.88569778583445], +[81.477329557709879, +280.27531853573242], +[81.155802685302064, +280.65973674038372], +[80.827253964986767, +281.03833630668606], +[80.491635388479281, +281.41082146447383], +[80.149044069286276, +281.77702810309711], +[79.7995779992868, +282.13681388863216], +[79.443346478369264, +282.49003760746535], +[79.08046556257105, +282.83655439054945], +[78.711033469494453, +283.17619662407293], +[78.335064351749338, +283.50870373016835], +[77.952552449006276, +283.8337769339455], +[77.563499298677243, +284.15110461185463], +[77.167912989511137, +284.46036208590982], +[76.765813273607833, +284.76121138215223], +[76.357183865027707, +285.05323365896641], +[75.941827302912714, +285.33571342443634], +[75.519521488672211, +285.60781398953264], +[75.090119775789688, +285.86867766070219], +[74.653625255389017, +286.11747421566378], +[74.210099790617107, +286.35337996069126], +[73.759670808800863, +286.57566815754876], +[73.30266721957824, +286.78403950109544], +[72.839500773537281, +286.97829600951161], +[72.370625172919176, +287.15823531773651], +[71.8965103365367, +287.3236873552861], +[71.417609498145453, +287.474500649151], +[70.934385705149879, +287.61062429856781], +[70.44739710596501, +287.73239132596507], +[69.9572031251955, +287.84024894378342], +[69.464323351373437, +287.93464087136397], +[68.9692100890504, +288.01597297177977], +[68.472269420922657, +288.08464722238], +[67.973872520193879, +288.14107503279911], +[67.474360908670064, +288.185661594757], +[66.974050470928447, +288.21885889979166], +[66.473223062586541, +288.241119328623], +[65.972122194903775, +288.25293433922309], +[65.470962157784385, +288.25480643314586], +[64.9699315901405, +288.24725886026306], +[64.469187900396875, +288.23090260450516], +[63.968851225731676, +288.20636881328574], +[63.469006688092541, +288.17429203827658], +[62.96971018761478, +288.13533058156327], +[62.470996113116982, +288.09014789748994], +[61.972874227731985, +288.03944395750153], +[61.475306665586892, +287.98406259433409], +[60.978215119613076, +287.92487757188007], +[60.481508463348405, +287.86268952297786], +[59.985136183447118, +287.79804438875431], +[59.4890559053342, +287.73142318634484], +[58.993229183402512, +287.66323169680345], +[58.497644867054, +287.59360452875563], +[58.0022982600788, +287.52260906453989], +[57.507183068336126, +287.45031961621896], +[57.012289186901889, +287.37683580919668], +[56.517605088008594, +287.30226298609023], +[56.023120560965417, +287.2266904774047], +[55.528832142134419, +287.150150714198], +[55.034738296220972, +287.07266251202287], +[54.540834711785493, +286.99425989299539], +[54.047105863030062, +286.91503096756111], +[53.553532872701979, +286.83507731230594], +[53.060095508605365, +286.75450756432281], +[52.566770119465119, +286.67345598639207], +[52.073531890637788, +286.59206336206813], +[51.580354578081547, +286.51047950795009], +[51.087207667221733, +286.42888683277306], +[50.594059626864677, +286.34747607817], +[50.100877859117425, +286.26644822584257], +[49.607625416382355, +286.18604109730364], +[49.114264882235574, +286.1065015541721], +[48.620760716244241, +286.02807198782057], +[48.12708201104752, +285.95097867299518], +[47.633200232293937, +285.8754440357398], +[47.139087118887787, +285.80169310027907], +[46.64471146032632, +285.72996016691667], +[46.150045032526009, +285.66048201464031], +[45.655066505062642, +285.5934801827791], +[45.159764822331717, +285.52911824498585], +[44.664132661515666, +285.4675452699841], +[44.168166738982869, +285.40889719133986], +[43.67187258004158, +285.35326035238995], +[43.175257946819862, +285.30070884348368], +[42.67832992606224, +285.25132244434036], +[42.181092765319136, +285.20520241654663], +[41.683551527278183, +285.16245571616577], +[41.185711202538094, +285.12319492526808], +[40.687572201730454, +285.0875534796491], +[40.189137912393115, +285.05567060770449], +[39.690418918668115, +285.02767137344387], +[39.1914361700312, +285.003623590326], +[38.692212310985454, +284.98358083676584], +[38.192770258652885, +284.9676008454951], +[37.693137341001531, +284.95575708756525], +[37.1933464568476, +284.94812692545634], +[36.693436601077579, +284.94472886568184], +[36.193449294772734, +284.945347849362], +[35.693418856280886, +284.949710359077], +[35.193371937334881, +284.95752286711951], +[34.693328573012082, +284.9684139270496], +[34.193300997213811, +284.98199177817395], +[33.693293784509173, +284.99775244670275], +[33.193301419722268, +285.01475296453481], +[32.693309756330123, +285.03193990499142], +[32.193285168107664, +285.04815130426039], +[31.693137586561082, +285.06180183939694], +[31.192793530364444, +285.07119842158573], +[30.692248512584793, +285.07476556353691], +[30.191594499571572, +285.07138705428883], +[29.690970381713761, +285.0600626133521], +[29.190549143144558, +285.03983031138876], +[28.690531950336151, +285.00986371629983], +[28.19116868918935, +284.96937204086856], +[27.692759187676309, +284.9176420106262], +[27.195620105457717, +284.85423195652544], +[26.700086709790092, +284.77876979486882], +[26.206518864657326, +284.690921292491], +[25.715296503751485, +284.590474723017], +[25.226809286131175, +284.47725292680411], +[24.741443556761141, +284.35113265417795], +[24.259546917220497, +284.21217735426961], +[23.781459854536994, +284.06049762051248], +[23.307520386443628, +283.89622623394888], +[22.838039777043164, +283.71956648210221], +[22.373309478573884, +283.53073687565671], +[21.913595116671988, +283.32998470831637], +[21.4591010727006, +283.11767643507278], +[21.010003499704016, +282.89420153435924], +[20.566446614500521, +282.65995794631039], +[20.128506564175485, +282.41538808217757], +[19.696233080721679, +282.16093842352433], +[19.269688398854182, +281.89700589135447], +[18.849004131926293, +281.62384582059235], +[18.434319660452644, +281.34167253483093], +[18.025772313384579, +281.050684148669], +[17.623520287197731, +280.7510518339185], +[17.227726109279494, +280.44294196619296], +[16.838514743304575, +280.12656332131695], +[16.455887603016013, +279.80225566102581], +[16.079803997733332, +279.47037981727419], +[15.710206248314526, +279.13128984156072], +[15.347013618728349, +278.78534335455458], +[14.990130495929217, +278.432886492336], +[14.639494746820324, +278.07420673812152], +[14.295173844800134, +277.70945149660815], +[13.957268801821597, +277.33873566602892], +[13.62588081883659, +276.96217284627966], +[13.301109354277646, +276.57987218704267], +[12.983055941484439, +276.19194290417761], +[12.671827553178312, +275.79849514875997], +[12.367541917014272, +275.39963605031471], +[12.070318436660624, +274.9954710055693], +[11.780278932818353, +274.58610538639834], +[11.497554663432862, +274.17164673505033], +[11.222281081489552, +273.75220321310587], +[10.954614948839511, +273.32786948915384], +[10.69477176944663, +272.89870426791111], +[10.44298592271471, +272.46476714155955], +[10.199492585988692, +272.026139585951], +[9.9645160984423544, +271.58293750392113], +[9.7382727543132184, +271.13527971325732], +[9.5209624469642762, +270.68328078080771], +[9.3127573849865861, +270.227059956458], +[9.1138285273331565, +269.76675715839178], +[8.9243228758704038, +269.30254276559072], +[8.7443070218643761, +268.83461934652485], +[8.5738154676513112, +268.36319017664306], +[8.4127821298913048, +267.88848540234369], +[8.26089927493512, +267.41081301620585], +[8.1177942874550073, +266.93048657517261], +[7.9830671436198264, +266.44780100704747], +[7.8562562767911945, +265.96302889079487], +[7.73686692496992, +265.47642694597226], +[7.6242554903291255, +264.9882652447435], +[7.5174267709537448, +264.49885726599547], +[7.4153099430278111, +264.00848346539192], +[7.3169662701793943, +263.51736493435072], +[7.221775767245985, +263.02565382081292], +[7.1292208426096169, +262.53347590422356], +[7.0390344627086154, +262.0409018692099], +[6.9515250360510219, +261.5478918171554], +[6.8671249307871864, +261.05438875402717], +[6.7861491038964843, +260.56036232806571], +[6.7086442891736322, +260.06582903874096], +[6.6345781140086766, +259.57081790744616], +[6.563781162484629, +259.07537630743542], +[6.4957770399223085, +258.57958900138044], +[6.4300260948257417, +258.08353982376377], +[6.3660768813958839, +257.58729313660592], +[6.3036756432011671, +257.09088290795523], +[6.24262783709737, +256.59433333731261], +[6.182845449828454, +256.09765483271445], +[6.1244766613295631, +255.60083088707682], +[6.0677165156800879, +255.10384221004014], +[6.0126824288807423, +254.60668157057702], +[5.9593197458524365, +254.10936309072056], +[5.9075231561949826, +253.61190579187598], +[5.8571041932048136, +253.11433470758189], +[5.8076914288151844, +252.61668792737561], +[5.7588766811349306, +252.11900318878332], +[5.7103073340299053, +251.62131112569546], +[5.6617531136090546, +251.12363037393587], +[5.6130181289670009, +250.62597652799735], +[5.5639517739477, +250.12836163793168], +[5.5145028990033, +249.6307894331097], +[5.4646419678015752, +249.1332618405462], +[5.4143238626788524, +248.6357830037289], +[5.3634692605892536, +248.13836215648226], +[5.3119882891461989, +247.64101021924523], +[5.2597703218037148, +247.14374044951492], +[5.2066591110663971, +246.64657110557405], +[5.1524947202778568, +246.14952171890855], +[5.0971753677933185, +245.65260574345317], +[5.0407267879544655, +245.15582109717582], +[4.98321257522486, +244.65916066433027], +[4.9247612141000721, +244.1626090946381], +[4.86564380224256, +243.66613290536208], +[4.806160926711712, +243.16969373343252], +[4.7465790893245909, +242.67325731123043], +[4.6870900485557039, +242.17679994316143], +[4.6278668556623561, +241.68030067766239], +[4.569073672318142, +241.18373978757427], +[4.51085508077123, +240.68710016531691], +[4.45334710330635, +240.19036631027868], +[4.3966524487683536, +239.6935269864623], +[4.3408004818633561, +239.19657909434483], +[4.2857972167675262, +238.6995221800467], +[4.2315984749427544, +238.20236152991481], +[4.1780499316484292, +237.70511438733229], +[4.124977851234501, +237.207799346105], +[4.0722642388947241, +236.71042954855054], +[4.0199132511584512, +236.21300744952293], +[3.9679643569805529, +235.7155323751166], +[3.91651052940833, +235.21799807716465], +[3.8657615110241932, +234.72038641878791], +[3.8159492217486362, +234.22267806424739], +[3.767260482578251, +233.7248590894277], +[3.71978378260978, +233.22692487619088], +[3.6735796947825805, +232.72887367085323], +[3.6286697872231031, +232.23070736721149], +[3.5849910167576375, +231.73243452767701], +[3.542464590744892, +231.234063896012], +[3.5010467427713339, +230.73560061752593], +[3.4607695912282987, +230.23704384417408], +[3.4216886875686, +229.73839117889122], +[3.3839047800504121, +229.23963719330155], +[3.3476160488965334, +228.74077048377396], +[3.3130334560026284, +228.24178155523725], +[3.2802839019641716, +227.74266967280454], +[3.2493131343212642, +227.2434471992357], +[3.2200125977184779, +226.74412891309743], +[3.1921798574356246, +226.24473330829147], +[3.1654114554579302, +225.74528701029507], +[3.1392688834672593, +225.24581505254318], +[3.1134138321859419, +224.74633601200324], +[3.0877222369938977, +224.24685835641361], +[3.0621312118390329, +223.74738776925417], +[3.0366643300541352, +223.24792597692502], +[3.0115295058082006, +222.74846636090098], +[2.9869701205624728, +222.24900114463037], +[2.9631663280080782, +221.74952631487849], +[2.9401636892792498, +221.25004473391763], +[2.9179713863318648, +220.7505609123005], +[2.896560984191443, +220.25108017280695], +[2.8758240057797306, +219.751609421797], +[2.8556331104916834, +219.25215558195347], +[2.83586060357778, +218.75272500429125], +[2.816377979665365, +218.25332324266054], +[2.7970573373483258, +217.75395560310989], +[2.7777768759100603, +217.25462822566692], +[2.7584278028121183, +216.7553493064143], +[2.7388970813150513, +216.25612792798623], +[2.7190122406930479, +215.75697626024561], +[2.69847265285331, +215.25791336137945], +[2.6769383843658776, +214.75896136880829], +[2.6539936035233791, +214.26014758483922], +[2.62905703213953, +213.76151023634407], +[2.6015146106907494, +213.26309620062122], +[2.570798765987873, +212.76495911730711], +[2.5364428195525375, +212.26715644663528], +[2.4980110694214241, +211.76975331848951], +[2.4551216496415913, +211.27282018046506], +[2.4075106288433448, +210.77642555650488], +[2.3549362666015754, +210.28064352903655], +[2.2971003055926529, +209.785562426886], +[2.2335705680842426, +209.29129668554339], +[2.1638770669379537, +208.79798146197655], +[2.0874743960372686, +208.30578099588777], +[2.0036318623651526, +207.81491039753931], +[1.9115807625108843, +207.32562560371005], +[1.8105734540141027, +206.83821974738294], +[1.6998967150435391, +206.35302464319545], +[1.5788510994200682, +205.87041602705779], +[1.4467222662208836, +205.39082456720902], +[1.3027238690205785, +204.9147605629052], +[1.146072961005949, +204.44280501308037], +[0.97605114999097153, +203.97559819643919], +[0.79205666469804648, +203.51382376611178], +[0.59353809736423524, +203.05821920762898], +[0.38001916756737669, +202.60956144721271], +[0.15115027207737836, +202.16864243518197], +[-0.093353181540137151, +201.73630087408816], +[-0.35372722747800045, +201.31340814807075], +[-0.63010666950619143, +200.90078084537183], +[-0.92257645810920175, +200.49929673894775], +[-1.230971472142474, +200.10979330459281], +[-1.5544307521991436, +199.73266113806918], +[-1.8919918112767706, +199.36808037077185], +[-2.2428110212903656, +199.01614782699073], +[-2.6062605433069472, +198.67699503455913], +[-2.981760043831466, +198.35085622125098], +[-3.3685641697976041, +198.03789687654225], +[-3.7661937313738818, +197.73863162656372], +[-4.1742749295517214, +197.45357669774631], +[-4.5924686525918093, +197.18317503113846], +[-5.0203250061791849, +196.92784431440381], +[-5.4572487564035335, +196.68804305969837], +[-5.9023873200570049, +196.46395423565176], +[-6.3544182497585755, +196.25439453759503], +[-6.8121132100372606, +196.05766639738385], +[-7.2744807097416642, +195.87200745947638], +[-7.7407302609325006, +195.69569962704469], +[-8.21024224718257, +195.52700671003583], +[-8.6824459313706, +195.36421828343097], +[-9.1565782435614977, +195.20586289732103], +[-9.63179079081862, +195.050525912834], +[-10.107307390971686, +194.89675183293656], +[-10.582717277856876, +194.74293066960723], +[-11.057725587087424, +194.5874058354396], +[-11.531912760465753, +194.42842254800209], +[-12.004432459637203, +194.26382235059216], +[-12.474248487033424, +194.0913340706538], +[-12.940288596172238, +193.9087370848043], +[-13.401562010466169, +193.71391627226151], +[-13.856912088558289, +193.5048449560839], +[-14.30500777635473, +193.27987366853159], +[-14.744840526955556, +193.03859168316092], +[-15.175569936319828, +192.78093062328659], +[-15.596347377834521, +192.50684174745155], +[-16.006122205512455, +192.21636105263542], +[-16.403803928643377, +191.90955536478987], +[-16.788470426681549, +191.58660537028149], +[-17.159755620114677, +191.24816361238419], +[-17.5174053285974, +190.89506248130658], +[-17.861093502851993, +190.52817705946376], +[-18.190468667674, +190.14834807709886], +[-18.505244249182233, +189.75633056660541], +[-18.805164186642472, +189.35277598731224], +[-19.089818324228325, +188.93821184243882], +[-19.358714112776831, +188.51318711095865], +[-19.611380037160323, +188.07833965937834], +[-19.847522847965944, +187.63439508709922], +[-20.066943919556824, +187.18205448168425], +[-20.269678621852634, +186.72205654329963], +[-20.456639376963306, +186.25546685949786], +[-20.629013225820977, +185.78337008163822], +[-20.787918117266628, +185.30670836471231], +[-20.934079650802378, +184.82612790825195], +[-21.068207308855346, +184.34216972413532], +[-21.190801592241062, +183.85525635079102], +[-21.301643020336382, +183.36562391945463], +[-21.400321738400329, +182.87348867660128], +[-21.486491243570789, +182.37910660658758], +[-21.560064144531722, +181.88279696762277], +[-21.621015404750448, +181.38488625067711], +[-21.669357787273288, +180.88569433280523], +[-21.705228126736866, +180.38553354584627], +[-21.728797167695802, +179.88471649117437], +[-21.740260876448129, +179.38355341966741], +[-21.739911356963393, +178.88232982242096], +[-21.728063957844718, +178.38130210514112], +[-21.705066232577263, +177.88070297290173], +[-21.671391264126889, +177.38074402032871], +[-21.627541347893676, +176.88160728141307], +[-21.574024229712421, +176.38344423892704], +[-21.511380715449508, +175.88637363378305], +[-21.440156986269852, +175.39048307876584], +[-21.360919250345166, +174.89583002643121], +[-21.274315139848508, +174.40243538867227], +[-21.181005864077552, +173.91028439650546], +[-21.08160110266823, +173.41934174192218], +[-20.976557303089567, +172.92958571937575], +[-20.86629113945936, +172.4409910952786], +[-20.751202883674154, +171.95352443689669], +[-20.631645726089882, +171.4671494534748], +[-20.507957567665816, +170.98182043510153], +[-20.380450294208295, +170.49748767893104], +[-20.249359699331677, +170.0141161627773], +[-20.11490246547001, +169.5316738525066], +[-19.977290587791391, +169.05012828092293], +[-19.836721924277079, +168.56944781835637], +[-19.693386861379764, +168.08959628180978], +[-19.547430769254497, +167.6105445597758], +[-19.398863119408162, +167.1323016051563], +[-19.247660726562604, +166.65488907845284], +[-19.093796123155826, +166.17833436730331], +[-18.937225725606623, +165.70267351906494], +[-18.777897814105661, +165.22794407403003], +[-18.615701800436792, +164.75420251279286], +[-18.450349683448657, +164.28157009499591], +[-18.281511568891663, +163.8101915048064], +[-18.108839198506839, +163.340226192152], +[-17.931922789522567, +162.87186055602803], +[-17.750347511105112, +162.40529691482047], +[-17.563794055409772, +161.94071863263474], +[-17.372211594348919, +161.47821596325187], +[-17.175614405770805, +161.01785340854968], +[-16.97402546133377, +160.55969199725052], +[-16.767493182104015, +160.10378547531144], +[-16.556073218940373, +159.65018157621486], +[-16.339845794416753, +159.1989111696752], +[-16.118965894057538, +158.74996328936308], +[-15.893605007854909, +158.30331464833827], +[-15.663926358525801, +157.85894290518485], +[-15.430074058342646, +157.41683612538014], +[-15.192197184385734, +156.97698265670977], +[-14.950555947189404, +156.53930456603638], +[-14.705725480376659, +156.10351608894774], +[-14.458347292056326, +155.66926424829379], +[-14.209067330634571, +155.23619167758559], +[-13.958568144512611, +154.80396498288428], +[-13.707546806619574, +154.3722510987964], +[-13.456783313278747, +153.94064437343951], +[-13.2073065746549, +153.50852782707761], +[-12.960210796820153, +153.07524024360714], +[-12.716633181442063, +152.64013558726367], +[-12.477824169475223, +152.20257847411114], +[-12.245070520466346, +151.76196850318689], +[-12.019588639742995, +151.31779910082233], +[-11.802349438742434, +150.86975520907174], +[-11.594276541092302, +150.41760678626909], +[-11.396308193269517, +149.96116657115434], +[-11.209394268379983, +149.50026799132203], +[-11.034513398494871, +149.03481286344444], +[-10.872579474318009, +148.56483631804491], +[-10.724205153240382, +148.09058765663576], +[-10.58992050050807, +147.61237369769833], +[-10.470243867530248, +147.13050411201129], +[-10.365666667564689, +146.64527698060755], +[-10.27682702321537, +146.15702812984722], +[-10.204046515547789, +145.66623470748], +[-10.147396224556099, +145.17343006028793], +[-10.106869626353516, +144.67912872052167], +[-10.082408437101199, +144.18382848377567], +[-10.073715855701558, +143.68805005929107], +[-10.080432360365224, +143.19228779760186], +[-10.10228320847202, +142.69700277902413], +[-10.139322243935428, +142.202662590441], +[-10.191705765917144, +141.70975382881858], +[-10.259638046614928, +141.2187815092926], +[-10.343530112909674, +140.73029355281443], +[-10.44385391231364, +140.24490460463704], +[-10.561035491538048, +139.76329001435118], +[-10.695319311385166, +139.28613029904457], +[-10.846886814218278, +138.81412495159208], +[-11.015901917595098, +138.34800740619846], +[-11.20248299802843, +137.88854332733385], +[-11.406731483560424, +137.43654150655198], +[-11.628699096127832, +136.99283261562431], +[-11.868313500825938, +136.55820541575787], +[-12.12543541171171, +136.13345270407621], +[-12.399852643963419, +135.719385251133], +[-12.691126039699189, +135.31671966888115], +[-12.998730968942882, +134.92609651564203], +[-13.32215095892739, +134.54813111163], +[-13.6608445721476, +134.18345216379913], +[-14.014257979307141, +133.83270869867133], +[-14.381844356583732, +133.496557961231], +[-14.763121216783368, +133.17570563288959], +[-15.157601548027797, +132.87092375340572], +[-15.564672190336562, +132.58296364087164], +[-15.983507475275715, +132.31232201518569], +[-16.413231148760836, +132.05924291712392], +[-16.852948013294579, +131.82366622551925], +[-17.301308012476269, +131.604490581837], +[-17.756775686690787, +131.39991125698705], +[-18.217969210086345, +131.20795820073545], +[-18.683740809748969, +131.02665243425403], +[-19.153114825928292, +130.85400724002949], +[-19.6251675905684, +130.68789915849345], +[-20.098842154543089, +130.52575566574541], +[-20.572986957433915, +130.36470012489406], +[-21.0464679181272, +130.20186592382649], +[-21.518252220941921, +130.03466394591655], +[-21.987336040460278, +129.8606979329476], +[-22.45272645135632, +129.67777011485813], +[-22.913661271970572, +129.48433929911266], +[-23.369455417175324, +129.27927784863394], +[-23.819367804876876, +129.06152838598905], +[-24.262738334601138, +128.82993691542134], +[-24.698798000591434, +128.583297681025], +[-25.126386737674032, +128.32049374127553], +[-25.543700694052344, +128.04049950672606], +[-25.948641864106371, +127.74228921717639], +[-26.339181917768457, +127.4249753523913], +[-26.71342467752627, +127.08822780764561], +[-27.069509471259032, +126.73217825868352], +[-27.40572743361821, +126.35728776518465], +[-27.721515019580576, +125.96491800615983], +[-28.01701286616137, +125.5568452207999], +[-28.292403638854811, +125.13478723521871], +[-28.547506390841932, +124.70021227672171], +[-28.781965050669644, +124.25438901191973], +[-28.995433113612354, +123.7984358151719], +[-29.18728421104862, +123.33321095106561], +[-29.356696391109075, +122.85957051302671], +[-29.502846139553625, +122.37853698553187], +[-29.625249935191388, +121.89126215553185], +[-29.723633856287204, +121.39890486340599], +[-29.797772438855432, +120.90260253104188], +[-29.8475765819046, +120.40353355772655], +[-29.873010574877753, +119.90290345646829], +[-29.874151131622888, +119.40190665543442], +[-29.851463153143072, +118.90163381973333], +[-29.805628701206807, +118.40310398400702], +[-29.737412244277213, +117.9072939512894], +[-29.647871461128652, +117.41503801029361], +[-29.538207866278881, +116.92699014348435], +[-29.409660139162327, +116.4436487484268], +[-29.26361883054112, +115.96536850822214], +[-29.101565493247357, +115.49234210431763], +[-28.924992890704637, +115.02459713534407], +[-28.735549878436629, +114.56195517247801], +[-28.5349639273632, +114.10408208407658], +[-28.324877110171325, +113.65056380517041], +[-28.106609428560834, +113.20099445467253], +[-27.88128429957845, +112.75492520493668], +[-27.649959946444536, +112.31185249447897], +[-27.413674345925166, +111.87130570927883], +[-27.173459421546642, +111.43283009187542], +[-26.930316935167887, +110.99596035403516], +[-26.685147016081824, +110.56023450761523], +[-26.438790570584381, +110.12518923092088], +[-26.1920769096191, +109.69034867577483], +[-25.945838376622827, +109.25520947689684], +[-25.700916074530387, +108.81926423898787], +[-25.458030828595131, +108.38211767013613], +[-25.217312087816225, +107.94376530249879], +[-24.978541276898902, +107.50439696970309], +[-24.741427073798384, +107.06421346272855], +[-24.505625860096316, +106.62340840310576], +[-24.270767354112969, +106.18217532475541], +[-24.036531305059874, +105.74068109219456], +[-23.802829455550739, +105.29897215624632], +[-23.569703184978234, +104.85702594411612], +[-23.337213103059987, +104.41480915660506], +[-23.105422387477, +103.9722910195126], +[-22.8743957545481, +103.52944247541507], +[-22.644221489563915, +103.08622129975767], +[-22.415090057512771, +102.64252706223387], +[-22.18725075726104, +102.19822777081637], +[-21.960963122636109, +101.7531897059811], +[-21.736488889671968, +101.30728399278541], +[-21.514091924077324, +100.86038631694505], +[-21.294051546755746, +100.41237060295285], +[-21.07670779083309, +99.963088796653366], +[-20.862437379625391, +99.5123828923324], +[-20.651624424276676, +99.0600981400113], +[-20.444653717484485, +98.606083711301167], +[-20.241913123313605, +98.150196080694684], +[-20.043799882203345, +97.692303278004914], +[-19.850734126821845, +97.232288860426053], +[-19.663151857185042, +96.770049222397191], +[-19.481492967662369, +96.305485981674309], +[-19.306198893792313, +95.838490755855275], +[-19.137721227014534, +95.368969154973882], +[-18.976475001056862, +94.896884238009633], +[-18.822650010229111, +94.422313604324245], +[-18.676287326459473, +93.9453793912863], +[-18.537398700855693, +93.466187604171111], +[-18.406002556133583, +92.984832500030834], +[-18.282127600561722, +92.5014217691704], +[-18.165721828222051, +92.016105067120932], +[-18.056342610241995, +91.5291116802338], +[-17.95328336250363, +91.0406852969154], +[-17.855784230508331, +90.551036388903867], +[-17.763065103613908, +90.060361611713], +[-17.674331838330666, +89.568845275813885], +[-17.588844286704092, +89.0766437750394], +[-17.506131674832744, +88.583858115368784], +[-17.425902255807472, +88.090556786300212], +[-17.347896884560438, +87.596801932730145], +[-17.271870056359742, +87.102653399399514], +[-17.197585065023809, +86.608169682390027], +[-17.1247050953835, +86.113423172509513], +[-17.052436245372636, +85.618547786256812], +[-16.979678485870703, +85.123715621822384], +[-16.905276907094027, +84.629095273447888], +[-16.828060692015576, +84.1348185893402], +[-16.74685005657987, +83.641018705585552], +[-16.660553289643204, +83.147878147113559], +[-16.568468962019384, +82.655613683821912], +[-16.470151679464259, +82.164438473975238], +[-16.36519798059544, +81.674552931005479], +[-16.253207605646949, +81.1861633248721], +[-16.133785038084035, +80.699493250448057], +[-16.006535462066051, +80.2147815353967], +[-15.871050806427156, +79.732277154078872], +[-15.726916080996748, +79.2522508220619], +[-15.573723401028836, +78.775000478465884], +[-15.411076971176634, +78.3008384708714], +[-15.238590467736397, +77.830101101511275], +[-15.055877324660793, +77.3631694928483], +[-14.862516757601671, +76.9004965765612], +[-14.658065198181781, +76.442589385335637], +[-14.442101418502267, +75.989979241750049], +[-14.214263885537452, +75.5432088806548], +[-13.974241330015406, +75.102847240366557], +[-13.721855391183549, +74.669441852345614], +[-13.45741856280601, +74.2432708401369], +[-13.181520026137759, +73.8244146593488], +[-12.894757960400293, +73.41289958891393], +[-12.597667969132782, +73.008752510946607], +[-12.290741758922874, +72.611997545372077], +[-11.974445260486505, +72.222648493782714], +[-11.649187409024947, +71.840739146352689], +[-11.315342788393831, +71.4663058022188], +[-10.973276826580594, +71.099365619477254], +[-10.623370021856738, +70.739895500144172], +[-10.266009857485953, +70.387840731579359], +[-9.90161188304674, +70.043090156713774], +[-9.5307400891527436, +69.705332285026117], +[-9.154025273043084, +69.374123509261537], +[-8.7720454513475321, +69.049019784419755], +[-8.3852079153177179, +68.7297342378005], +[-7.9938221424612177, +68.416067557571651], +[-7.5980858901141861, +68.107938209026173], +[-7.19780841515712, +67.805766125835646], +[-6.7926128444591827, +67.510259697281924], +[-6.3821776943338557, +67.2221179114584], +[-5.9664199899597978, +66.941753483763719], +[-5.5453834966498, +66.669423200805539], +[-5.1192035668939058, +66.405258109134721], +[-4.68830972495624, +66.1488994134142], +[-4.2532529797145724, +65.899719052148967], +[-3.8145321543612569, +65.657097255441357], +[-3.3724711486964849, +65.420672637175755], +[-2.9273033782278546, +65.190215471336288], +[-2.4792083364608, +64.965570875018727], +[-2.0282181740830563, +64.746858358534851], +[-1.5743035562582408, +64.534338247863218], +[-1.1174584491228761, +64.328254749258278], +[-0.65776469880494348, +64.128681869517436], +[-0.19534225469594374, +63.93560678040982], +[0.26967765413618289, +63.748977644310791], +[0.73712403654659642, +63.568624542324322], +[1.2068127873969046, +63.394319376034559], +[1.6785669300871835, +63.225823013927794], +[2.1522227316261073, +63.062891442517007], +[2.6276279068815045, +62.905276235558141], +[3.1046351753390788, +62.752713109785972], +[3.583087071084333, +62.604880864879441], +[4.0628270966580331, +62.461429257438866], +[4.5437144709140114, +62.32202800900351], +[5.0256448303814008, +62.18645465112548], +[5.50853211322402, +62.054536076354879], +[5.9923040146085205, +61.926128967114352], +[6.4769246066126254, +61.80119537494933], +[6.96237352938757, +61.67974582582405], +[7.4486212299304695, +61.561758673324974], +[7.9355955084459895, +61.447050347384533], +[8.4232091217941072, +61.33536237182], +[8.911376015430454, +61.226407946519849], +[9.40000623518781, +61.119821384146448], +[9.8890102127270438, +61.015201221627358], +[10.378300633083835, +60.912128752484932], +[10.867789424252424, +60.810131361112589], +[11.357390445284812, +60.70871185972797], +[11.847006285609803, +60.60736387577137], +[12.336482931315306, +60.505555789919981], +[12.825639691655851, +60.40274525594301], +[13.314315147133836, +60.298376084072125], +[13.802446227436267, +60.191833502245686], +[14.290008090959127, +60.082476031959885], +[14.776907309988671, +59.969716471006045], +[15.262774484488823, +59.853218250651679], +[15.747114356627367, +59.732768901309726], +[16.22968146110377, +59.608019729366688], +[16.710233954076543, +59.474650962194978], +[17.189663200290312, +59.335237880716193], +[17.668360585766305, +59.192138952249891], +[18.146941311930892, +59.0485968786554]], +"Racing":[[18.923648729985622, +58.929820042522763], +[19.406266149256961, +58.79912793635], +[19.885330681699067, +58.655961219856856], +[20.361025466779406, +58.5019682236684], +[20.833648572681707, +58.3387911443789], +[21.303584291970775, +58.168028209262374], +[21.771294865629258, +57.99126130449077], +[22.237242153866362, +57.809897143518221], +[22.701693164175051, +57.624734669426886], +[23.164872688975734, +57.43641407350151], +[23.627055047268467, +57.245659202115085], +[24.088675209795809, +57.053547747982961], +[24.55021567599125, +56.861244867632806], +[25.012099603331468, +56.669768414572012], +[25.47450129855126, +56.479545754888861], +[25.937529521662945, +56.290853285556921], +[26.401289346283995, +56.103966143555326], +[26.8658808126942, +55.919156120472394], +[27.331400077023464, +55.736695746824381], +[27.797960481447433, +55.556914317209007], +[28.265752057867651, +55.38036116695217], +[28.734974747065372, +55.207647406785661], +[29.205808909060782, +55.039376371407016], +[29.678394528397614, +54.876089134126261], +[30.152851013142534, +54.718320777586719], +[30.629276634951442, +54.566602777847145], +[31.107741349331231, +54.421443760371695], +[31.588292744213977, +54.283350060322384], +[32.070940128114735, +54.152770875526656], +[32.555610957847378, +54.029915179423639], +[33.042209746952452, +53.914933093110484], +[33.530618451106861, +53.80789952138862], +[34.020657067747969, +53.708594877293187], +[34.512143647369378, +53.616724277624279], +[35.004921566288566, +53.532053421832025], +[35.498883082429622, +53.454585953540409], +[35.993928545337141, +53.384377489812522], +[36.489904464506914, +53.321072886964991], +[36.986493053092865, +53.262766385842113], +[37.483391929214989, +53.207165105134386], +[37.980344358292292, +53.1520448082437], +[38.477130404316583, +53.095445989360506], +[38.973521445541124, +53.035483431117633], +[39.469309569908738, +52.970724384044985], +[39.964481821746652, +52.901412528338653], +[40.4590929780135, +52.828203485326028], +[40.953193598607569, +52.751624537930091], +[41.446769736090133, +52.671735022852154], +[41.939789117157382, +52.588478769386356], +[42.432216592503309, +52.501790464305635], +[42.92400924537845, +52.411570574585362], +[43.415119970897464, +52.317709816701729], +[43.905486739614304, +52.22003742583027], +[44.394998330354866, +52.118166399181611], +[44.883527357689559, +52.011682923710396], +[45.371106923936466, +51.900930525473335], +[45.858391704214526, +51.788888731092591], +[46.34620447228297, +51.679173259061315], +[46.835275571058013, +51.575217757507914], +[47.326090403226431, +51.479844192391774], +[47.818959528334709, +51.395743413920265], +[48.313982485309886, +51.32543453193778], +[48.810979094085567, +51.270812407751713], +[49.309580602051639, +51.233612562048037], +[49.809238178147069, +51.2155278753993], +[50.30921386541948, +51.218003844261688], +[50.808594811476162, +51.242458110943659], +[51.306347069660674, +51.28962010054402], +[51.801641409459677, +51.35794436730896], +[52.293932185899109, +51.445334639693158], +[52.782859029362932, +51.549926193666472], +[53.268088186880028, +51.670519505674193], +[53.749357007408832, +51.806062235018544], +[54.226564417122511, +51.95528229740313], +[54.700006365887148, +52.116056359990594], +[55.170192384634483, +52.286121814506231], +[55.637678412635431, +52.463476749291061], +[56.102838489676607, +52.646847028470013], +[56.566021997374094, +52.83515528356449], +[57.027501126424255, +53.027602402704879], +[57.487200530620939, +53.224262325648468], +[57.944952267868551, +53.425413611266656], +[58.400628189589447, +53.631224200930617], +[58.854251045721888, +53.8415215202376], +[59.305886673113157, +54.056053643436194], +[59.755605656797343, +54.274575303639985], +[60.20347979669166, +54.496853825759324], +[60.649584584853628, +54.722662595276645], +[61.093990483499056, +54.951796923198749], +[61.536740776255904, +55.184114321638212], +[61.977874546328195, +55.419486910408231], +[62.417447232324413, +55.657762412696776], +[62.855561081183012, +55.898709963653431], +[63.292333238188121, +56.142081383873837], +[63.727886961272347, +56.387626926044263], +[64.162356253348534, +56.63508637145933], +[64.595879579307692, +56.884199473792179], +[65.028588940614, +57.134723858437205], +[65.460589846918751, +57.386468000997709], +[65.891984012482, +57.6392505328223], +[66.3229021469395, +57.892843791700535], +[66.753561802446214, +58.146875799061085], +[67.184204737779282, +58.400936122233183], +[67.615110016280312, +58.6545510628423], +[68.046670938272, +58.907048360119418], +[68.4793007107747, +59.157709399539712], +[68.91335373084074, +59.405897423979326], +[69.3490195295428, +59.651243090795177], +[69.786443077037035, +59.893440700087623], +[70.2257615631499, +60.13218358634564], +[70.667101454326414, +60.367168373962514], +[71.11058028653963, +60.598090736503664], +[71.5562937232173, +60.8246697903208], +[72.004285773173649, +61.046709421338605], +[72.454586665590057, +61.264028238426178], +[72.907265866356056, +61.476347725568516], +[73.362526634172966, +61.683072734619358], +[73.820582644007942, +61.8835270769678], +[74.281550619323866, +62.077191437589484], +[74.745296437658425, +62.264106879859241], +[75.211633669695757, +62.444460394785814], +[75.680355980887626, +62.618522444669367], +[76.151173857745235, +62.786835006576787], +[76.623795379387445, +62.950015359309717], +[77.097947954160588, +63.108692888700865], +[77.573371493722163, +63.263521590759453], +[78.04981896675406, +63.415170858833783], +[78.527019767575212, +63.564433432167363], +[79.004591753095056, +63.712504356250811], +[79.482131660193431, +63.860678409937528], +[79.959245211974448, +64.010218879953385], +[80.435560671574081, +64.162281160086138], +[80.91069138460216, +64.31800373748419], +[81.3840768965078, +64.4789475910872], +[81.854577658577185, +64.64812956036441], +[82.320755248614248, +64.828872897328921], +[82.781155119941559, +65.023860547419673], +[83.234923437835022, +65.23381664637202], +[83.681346998617059, +65.4589657711484], +[84.119710762508149, +65.699429034482563], +[84.549404490994888, +65.95506140352316], +[84.969845307748471, +66.225640596064224], +[85.380381899774633, +66.511020139306979], +[85.7801099797982, +66.811348269598653], +[86.168010091977266, +67.126801534265581], +[86.543102063196827, +67.45737992345336], +[86.904703355677213, +67.8026618006961], +[87.252210596481959, +68.162123450172885], +[87.584993026253244, +68.535256261133839], +[87.902362384979185, +68.921581177213085], +[88.203596980974027, +69.320612713903245], +[88.488125152563782, +69.731724117434624], +[88.7558375067844, +70.153979833149251], +[89.006763311304482, +70.586421450401247], +[89.240574574779714, +71.028346234775853], +[89.455661706915734, +71.479674140307353], +[89.6500628707691, +71.94028381600647], +[89.821595006287211, +72.4098785914347], +[89.967738279939923, +72.887969911052465], +[90.08580090000801, +73.373749735943591], +[90.1748401905081, +73.8656973204141], +[90.239349283428638, +74.3614819201392], +[90.285167529455677, +74.859359426115148], +[90.317936338203992, +75.35827702618144], +[90.342674966141018, +75.857663304087382], +[90.364172698019473, +76.357200936248191], +[90.385282403600655, +76.856754541675912], +[90.403595074297058, +77.356415223159445], +[90.415480665468593, +77.856264500780327], +[90.417770062545458, +78.356245021950386], +[90.4085396556911, +78.856140603132644], +[90.3861952463939, +79.355617183480675], +[90.34968459103554, +79.854258644450113], +[90.2992486669264, +80.351686052762119], +[90.235438386445978, +80.84757643084032], +[90.158704085108923, +81.341632349528879], +[90.069246930128728, +81.8335439084577], +[89.967230025710307, +82.323005525983177], +[89.852991768286756, +82.809761933570584], +[89.727324135568722, +83.293695948655028], +[89.591098710216855, +83.77476670382768], +[89.445064993602557, +84.252952499752681], +[89.289712504855686, +84.728193431334176], +[89.1254812836577, +85.2004407520958], +[88.9529673478663, +85.669727909518386], +[88.773145684294491, +86.136265953287221], +[88.58704441222109, +86.600336483858385], +[88.3954674192585, +87.062173980951755], +[88.1987203354492, +87.521833025087659], +[87.996965800699144, +87.979316290141426], +[87.790131260345674, +88.434524121930238], +[87.577610775549175, +88.887103535896514], +[87.358709838197569, +89.33662995703888], +[87.132984913524, +89.7827687917597], +[86.900537742458837, +90.225442789959331], +[86.661613108395557, +90.664655266594451], +[86.416629597758543, +91.10051911414449], +[86.166392332340692, +91.533389971000261], +[85.911758282335981, +91.963690488460813], +[85.653348294082235, +92.391734295891524], +[85.391288596520369, +92.817553401082], +[85.125571170984472, +93.241099450763656], +[84.856026731952568, +93.662219246645236], +[84.582139729993969, +94.080526229076483], +[84.303352042771337, +94.4955818396185], +[84.019355530908115, +94.907091260451438], +[83.73035726955969, +95.315104308393785], +[83.43668416895072, +95.719766400567408], +[83.1387069914538, +96.121270785735192], +[82.836896395218474, +96.519902663591381], +[82.531734731362718, +96.915975983153842], +[82.22366015830346, +97.309788461630475], +[81.913030074153767, +97.701588885051137], +[81.60018741648372, +98.0916254115757], +[81.285535131020552, +98.480204127823725], +[80.969607399587517, +98.8677470057093], +[80.652947669595932, +99.2546921961692], +[80.335953915876516, +99.641363819375755], +[80.018725035772761, +100.02784257074561], +[79.701281605984661, +100.41414511427735], +[79.383579189949714, +100.80023465293579], +[79.065438461546933, +101.18596302298455], +[78.746659285713548, +101.57116384569996], +[78.427121963370141, +101.95573601124019], +[78.1068721156904, +102.33971507033006], +[77.785998339967961, +102.72317294000153], +[77.4646251075963, +103.10621237888729], +[77.142951469854779, +103.48899961226232], +[76.821187599544118, +103.87171100589931], +[76.49949662985081, +104.25448367372765], +[76.177944791578582, +104.63737322279465], +[75.8565817133409, +105.02042120260452], +[75.535504188755084, +105.40370852300865], +[75.214906532707346, +105.78739722910717], +[74.894995266068435, +106.17165833024265], +[74.5758903198378, +106.55658932111174], +[74.257531659887491, +106.94213781298491], +[73.939821473095847, +107.3282208886676], +[73.6226992624225, +107.71478705865471], +[73.306181941828839, +108.10184864821942], +[72.990289334393708, +108.48942026953276], +[72.674923001415635, +108.87742034126956], +[72.3597418099166, +109.26557084296752], +[72.044339314250351, +109.65354143047495], +[71.728246701322178, +110.04094959683015], +[71.410869033709758, +110.42730503630554], +[71.091607974410451, +110.81210482709815], +[70.770038234618667, +111.19497718807254], +[70.446076884332967, +111.57582802503417], +[70.119719574328457, +111.95462769404762], +[69.7909542137437, +112.33133919942256], +[69.4597527244625, +112.70591058505147], +[69.126086142439789, +113.07828768358554], +[68.789942350364356, +113.44843014751649], +[68.451341902437079, +113.81632666165356], +[68.110312358557678, +114.18197262654559], +[67.766878094553249, +114.54536088913478], +[67.4210574594567, +114.90647888964165], +[67.072871112744053, +115.26531647825038], +[66.722366999797117, +115.62189065122726], +[66.369646649823, +115.97627289661017], +[66.014821268249378, +116.32854765087772], +[65.6579906662149, +116.67879123883702], +[65.299234052527524, +117.02706186140689], +[64.938633323361415, +117.37342291362719], +[64.5763299300401, +117.71800295949217], +[64.212582946844719, +118.06105918186326], +[63.847673567889977, +118.40287902212792], +[63.481864058605119, +118.74373559881684], +[63.115383261018408, +119.08387046859377], +[62.74845682724586, +119.42352465604274], +[62.381350735314591, +119.76298468981614], +[62.014412247669661, +120.10262577839991], +[61.648003456173939, +120.44283800197402], +[61.28245412649008, +120.78397325641947], +[60.91802885591769, +121.12630873485189], +[60.554983605885965, +121.47010696090341], +[60.193612625099419, +121.8156639568594], +[59.8342857234808, +122.16334517570604], +[59.477389126308012, +122.51351979695107], +[59.12326501489062, +122.86649732700204], +[58.772157750191951, +123.22247531590646], +[58.424300382233248, +123.58162904733072], +[58.079994785857558, +123.94418789594874], +[57.739686195715223, +124.31049958913533], +[57.403876850810192, +124.68093842321301], +[57.073192762744164, +125.05595647421849], +[56.748515410033114, +125.43618302955137], +[56.430783908409225, +125.82222939461515], +[56.120696569576779, +126.21444248171861], +[55.818356019230649, +126.61265885385953], +[55.523705740943988, +127.0165997915217], +[55.236591535704704, +127.42593364400848], +[54.956645223210408, +127.84020477160568], +[54.683451629136442, +128.25896126558916], +[54.416773085457457, +128.68189644228357], +[54.1568272585394, +129.10900220228203], +[53.903954837268927, +129.54033287144966], +[53.658580585292114, +129.97597146059766], +[53.421327849408165, +130.41608437924714], +[53.192871679711317, +130.86082591283204], +[52.973764083635743, +131.31024693610777], +[52.764200392259731, +131.76419723958259], +[52.564287607493533, +132.2224800807742], +[52.374108905385931, +132.68488790885345], +[52.193684944208549, +133.15118911530624], +[52.023020065920718, +133.62115053447368], +[51.862149038613929, +134.09455434542267], +[51.711199859942596, +134.57121500860094], +[51.57032464918035, +135.05094995791222], +[51.439679355416729, +135.53357161166821], +[51.319426468523886, +136.01888751523373], +[51.209731939539047, +136.50669879999435], +[51.110763543387478, +136.99679930207304], +[51.022700227741446, +137.48897675618247], +[50.945724098275868, +137.98301020153079], +[50.880041020210832, +138.47867205454693], +[50.825941798246, +138.97573226308154], +[50.783739306046151, +139.47394435652714], +[50.753703160282669, +139.97303856654531], +[50.735916933414877, +140.47272022091263], +[50.730423542987516, +140.97268908802238], +[50.737150284037185, +141.4726438242358], +[50.755625038324176, +141.97230239111326], +[50.785112890707595, +142.4714313429379], +[50.825055670960275, +142.96983199230471], +[50.875261799508607, +143.46730287105217], +[50.935638093154125, +143.96364140607923], +[51.006281879338474, +144.4586221044745], +[51.088055969656736, +144.95188463715479], +[51.182023989039664, +145.44296799980125], +[51.289183612228733, +145.93134000482598], +[51.41033975681767, +146.41642676989468], +[51.546226372378278, +146.89759213025863], +[51.6973083616048, +147.37420211425919], +[51.862999615010139, +147.84593205739316], +[52.0424109182585, +148.31261718349108], +[52.23468391128511, +148.77415297205843], +[52.439046586496879, +149.23046499763149], +[52.654771906103235, +149.68151713225106], +[52.881306465765952, +150.12723883561574], +[53.11875160120087, +150.56724337475222], +[53.367422448476589, +151.00099995914155], +[53.62752198846394, +151.42799904284487], +[53.898814077070668, +151.8479756610293], +[54.180900937197663, +152.26077943202517], +[54.473327550456318, +152.66632484668492], +[54.77543348103265, +153.06471397611747], +[55.086493424439155, +153.45615401566573], +[55.405780698569259, +153.84091496694955], +[55.732486664369048, +154.21939963064767], +[56.065795157941608, +154.59208578119129], +[56.405037222389737, +154.95938109867873], +[56.750066814159347, +155.32124472861079], +[57.100951127216511, +155.67743301601402], +[57.457819355857659, +156.02762425423168], +[57.820991405340919, +156.37127066162273], +[58.190850253779061, +156.70770593202644], +[58.567636680194511, +157.03636113686179], +[58.951061749110679, +157.35724820480476], +[59.340614724526652, +157.67067048740557], +[59.735774210480912, +157.97699670402639], +[60.136005296592124, +158.2766693202712], +[60.540782782788511, +158.57017496221385], +[60.949651444143861, +158.85795646192813], +[61.362376320525122, +159.14018030804891], +[61.778827617945751, +159.41687606462958], +[62.198909894646548, +159.68802750934816], +[62.62260958709971, +159.95349006443857], +[63.049948845526444, +160.21305199623544], +[63.480898018317333, +160.46657478906957], +[63.91521101816511, +160.7142929437467], +[64.352543742964684, +160.95664280403454], +[64.792558562747374, +161.19409068399165], +[65.234949486940977, +161.42708381252473], +[65.6794325835177, +161.65606238484935], +[66.125741141656619, +161.88146392360107], +[66.573636172931543, +162.10369769231298], +[67.022896181334218, +162.32316018872322], +[67.4732970366035, +162.54027284805173], +[67.924573001873469, +162.75556183808339], +[68.376438654926773, +162.9696112659627], +[68.828621689503876, +163.18298989327872], +[69.280904907632177, +163.39615623213894], +[69.733100121894537, +163.60950915475829], +[70.185005787701954, +163.82347445387427], +[70.636345082982061, +164.03863119102405], +[71.086796431616037, +164.2556395780291], +[71.536058282457773, +164.47509852400376], +[71.9839692347475, +164.69730104933384], +[72.430443855587157, +164.92237536846574], +[72.875427114361457, +165.1503838345522], +[73.318956453427631, +165.38120825065866], +[73.761122022238936, +165.61463505742219], +[74.201993485205548, +165.8504972742027], +[74.6415057872289, +166.08888219357044], +[75.079518411356759, +166.33001091585885], +[75.515871335179114, +166.57412950930893], +[75.950378158309007, +166.82151811500802], +[76.382834634720368, +167.07247264394422], +[76.813055256685018, +167.32724027948979], +[77.240970223742522, +167.58586185850066], +[77.666573050317936, +167.84827126784523], +[78.089862410211708, +168.11439658183195], +[78.510816027544962, +168.38420139352451], +[78.92940022085854, +168.65766776534258], +[79.345599781908021, +168.93475002901556], +[79.759487873447142, +169.2152739262807], +[80.171187177979974, +169.49900106467521], +[80.580824571176493, +169.78569769791034], +[80.98850057561863, +170.07517701240243], +[81.39430328574592, +170.3672769442947], +[81.798337715631959, +170.66181832669449], +[82.20078202263818, +170.95852926414105], +[82.601854524272952, +171.25709246463109], +[83.001803449101146, +171.55715962749886], +[83.400970623655638, +171.85826646983557], +[83.799746972568784, +172.15989103786353], +[84.198483141518579, +172.46156879133866], +[84.597322435792108, +172.76311018170489], +[84.996302979009016, +173.06446465038402], +[85.395446198585546, +173.3656036163016], +[85.794762849999316, +173.666512567854], +[86.19425830266853, +173.96718409578156], +[86.593940493292962, +174.26760734605483], +[86.993831488269464, +174.56775259400376], +[87.3939604121492, +174.86758057013139], +[87.794360147997892, +175.16704678507247], +[88.195075884394626, +175.46609000358723], +[88.59615886606656, +175.76464045426718], +[88.997651470147119, +176.06263978794374], +[89.399555385105018, +176.36008417026966], +[89.801851925044289, +176.65699732169193], +[90.20451014188157, +176.95341982098628], +[90.60745796544046, +177.24944856097758], +[91.010602783276823, +177.54520900534729], +[91.413870379759288, +177.84080203612982], +[91.817276523674522, +178.13620594960784], +[92.220882340381465, +178.43133697384064], +[92.624768719330149, +178.72608389493564], +[93.029075432810757, +179.0202538731493], +[93.433971343767382, +179.31361218612994], +[93.83959605697568, +179.60596179962485], +[94.2459513017543, +179.89729519091671], +[94.652969619134808, +180.18770158194144], +[95.060569166065619, +180.47729171197457], +[95.468644550615579, +180.76621103200227], +[95.8770787977991, +181.05462290302958], +[96.285768715155342, +181.34267241706007], +[96.694675192735161, +181.63041443462353], +[97.103791663158688, +181.91785780316209], +[97.513114674525156, +182.20500697978687], +[97.9226351860413, +182.49187442327604], +[98.332341324300842, +182.77847669506968], +[98.742226265187526, +183.06482319516084], +[99.152306414218415, +183.35089005704535], +[99.562610002863877, +183.63663633631469], +[99.973150538350353, +183.92204207794538], +[100.38387169924675, +184.2071878535719], +[100.79468142361875, +184.49220604239696], +[101.20552316189151, +184.7771780863475], +[101.61651366452334, +185.06193550423382], +[102.02785882174864, +185.34618023860344], +[102.43977899917692, +185.62959079701156], +[102.85250679112674, +185.91182357814014], +[103.26627919961462, +186.19252215374834], +[103.68132730532984, +186.47133037761509], +[104.09786440159414, +186.74790843630797], +[104.51609173547229, +187.02192310564516], +[104.93623121376953, +187.29299574676654], +[105.35861528196857, +187.56055538728259], +[105.7836249857219, +187.82392162969646], +[106.21157419375251, +188.08248136539967], +[106.64251699961049, +188.33601990234175], +[107.07637313148372, +188.58454052660417], +[107.5130515601365, +188.82806815625639], +[107.95248878946227, +189.06658155521706], +[108.39463577024117, +189.30003324860044], +[108.83942480200835, +189.52841104886917], +[109.28670377030454, +189.75187423924285], +[109.73627998687962, +189.9706804580093], +[110.18795228201479, +190.18512802757471], +[110.64148309051538, +190.39561863393845], +[111.09662043133855, +190.60261456222796], +[111.55312498596591, +190.80657925993791], +[112.01079028043866, +191.00792721410673], +[112.46943002990537, +191.20704658232589], +[112.92886086193398, +191.40433474063386], +[113.38888391010858, +191.60023886485291], +[113.84929274231371, +191.79523518894703], +[114.30988675048468, +191.98979401573573], +[114.77048775067607, +192.18433634178891], +[115.23092957095827, +192.37925498200957], +[115.69104365317217, +192.57494568546946], +[116.15064556290329, +192.7718357066835], +[116.60953950652527, +192.97036938823337], +[117.0675314808374, +193.17097406488676], +[117.52445678689298, +193.37399572765602], +[117.98016510970666, +193.57973363442167], +[118.43448724857849, +193.78851360229197], +[118.88717400717741, +194.00081413170108], +[119.33792281290732, +194.21719627840929], +[119.78645024814341, +194.4381439239562], +[120.23264068052818, +194.66377369347623], +[120.67647773245479, +194.89399877997477], +[121.11799681153312, +195.12863942233872], +[121.5573925376963, +195.36723491012515], +[121.99495730971418, +195.60917407611157], +[122.43094392450898, +195.85394710978352], +[122.86532468674886, +196.10155826004706], +[123.29791127174391, +196.3522897474005], +[123.72847570555916, +196.6064769111394], +[124.15673641248458, +196.86452494817331], +[124.58237566303926, +197.12687259104837], +[125.0050786469923, +197.39392368864617], +[125.4246081385289, +197.66593201030341], +[125.84076573909681, +197.94307075974126], +[126.25335461554127, +198.22549414382604], +[126.66218173013908, +198.51333523946079], +[127.06705258343813, +198.80671428026903], +[127.4677513498617, +199.10576551875079], +[127.86398798199303, +199.41070289279915], +[128.25542571121034, +199.72177487975102], +[128.64169476656667, +200.03924044268035], +[129.02234831547315, +200.36341562462061], +[129.39688546923139, +200.69463599436963], +[129.76476174398124, +201.0332364007557], +[130.12535255840305, +201.37958187867491], +[130.47797414159817, +201.73403425867431], +[130.82179504545772, +202.0970250420161], +[131.15543569712247, +202.46938507529291], +[131.47717065860724, +202.85206742965229], +[131.78530676635671, +203.24577176081806], +[132.078916195417, +203.65042293175532], +[132.35742594848, +204.06561111403818], +[132.62030703126879, +204.49086669949111], +[132.86702791805689, +204.92569730129856], +[133.09706586821522, +205.36957954126905], +[133.30988969834405, +205.82196749599507], +[133.50493212830605, +206.28230086979724], +[133.68158417432633, +206.7499992101136], +[133.83939191270065, +207.22438807957738], +[133.9786967928232, +207.70454126447063], +[134.10020267404769, +208.18951010909367], +[134.20450643190389, +208.67847152411852], +[134.29146352814254, +209.17081421535079], +[134.36063117395477, +209.66596876854737], +[134.41162165548886, +210.16332361457043], +[134.44440683843652, +210.66221058805658], +[134.45909789120387, +211.16195919171128], +[134.45582897243992, +211.66191429011684], +[134.4347922464375, +212.1614386988559], +[134.39620442605985, +212.65991584269688], +[134.3402779256416, +213.15674764297361], +[134.26719706884271, +213.65134818898377], +[134.17713687957684, +214.14314125397937], +[134.07025471114895, +214.63155502631793], +[133.94664044146629, +215.11600472270331], +[133.80635833059645, +215.59589318790728], +[133.64955032710793, +216.0706388818472], +[133.47667489266968, +216.53977385822125], +[133.28829585218142, +217.00290270954991], +[133.08495385711836, +217.45966116251168], +[132.86711141177321, +217.90968544355673], +[132.63519846328353, +218.3526237737415], +[132.38970793136178, +218.78818474633275], +[132.13141281386717, +219.21627884078185], +[131.86116485541083, +219.63693189167202], +[131.57982211157091, +220.05024917262395], +[131.28834882724689, +220.45648858167846], +[130.98772064489219, +220.85600320334962], +[130.67883309442314, +221.24916920090911], +[130.36237036977951, +221.63626557150772], +[130.03893411252253, +222.01755586091656], +[129.70907025265245, +222.39330048557579], +[129.37318131596578, +222.76366977528687], +[129.03161636331023, +223.12881176631316], +[128.68477058917051, +223.48894212033861], +[128.33326716248661, +223.84452911851844], +[127.97779004946536, +224.1961448981138], +[127.61905788012115, +224.5444402324251], +[127.25797797152931, +224.8903021847805], +[126.89550840173763, +225.23470825438216], +[126.53242706478702, +225.57846964740713], +[126.16880189208003, +225.92165573051221], +[125.80446728009409, +226.26408851054336], +[125.43922834512205, +226.60555650107526], +[125.07282871736905, +226.94577862722255], +[124.70499438911727, +227.28444893085046], +[124.33556678286364, +227.62138043241535], +[123.96484801129415, +227.95689099457763], +[123.59328618080946, +228.29146789340183], +[123.22134825701868, +228.62562678099749], +[122.8495542719858, +228.95994583084698], +[122.478442807909, +229.29502223258436], +[122.1084975999419, +229.63138558518469], +[121.73996370275169, +229.96929449494428], +[121.37300864814044, +230.30891718593841], +[121.00785356595298, +230.65047424452752], +[120.64495581608386, +230.99442825508893], +[120.28486006278726, +231.341314015563], +[119.92803101556059, +231.69155860291684], +[119.5745375739107, +232.04516941297544], +[119.22431229500216, +232.40201751119997], +[118.87734040059847, +232.76202978105005], +[118.5338745947594, +233.12538812334475], +[118.19426554858639, +233.49235316459576], +[117.85874096789826, +233.86305608727849], +[117.52696060645046, +234.23711449242441], +[117.19837654242239, +234.61398451188234], +[116.87240605644855, +234.99311806551458], +[116.54842221089832, +235.37395123871391], +[116.22577802054049, +235.75592045062248], +[115.90395240035343, +236.13857980303391], +[115.58296701999981, +236.52194421885403], +[115.2630345635711, +236.90618769020134], +[114.94439725676804, +237.29150573820868], +[114.62735514186173, +237.67813720332995], +[114.31223099983974, +238.066333274697], +[113.9992359254404, +238.45624784973302], +[113.6880999541165, +238.84764777167007], +[113.37837817335188, +239.2401680060255], +[113.06957831973465, +239.63341415708362], +[112.76108222037657, +240.02689877952898], +[112.45222663870508, +240.42010127376727], +[112.14246874392641, +240.8125931918467], +[111.83177256911573, +241.20434279533575], +[111.52028252829724, +241.59546152527591], +[111.20814244107632, +241.98606170863135], +[110.8954360453853, +242.37620868285489], +[110.58222549115391, +242.7659510464425], +[110.26857866631326, +243.1553424182469], +[109.95459475483622, +243.54446204849347], +[109.64038402948637, +243.93339856364528], +[109.32607927048825, +244.3222591009534], +[109.01190275808443, +244.71122325789503], +[108.69810911229364, +245.10049632599646], +[108.38488058478072, +245.49022422657563], +[108.07208833645159, +245.8803024009691], +[107.75949161058881, +246.27053730785028], +[107.44683213688127, +246.66072194650971], +[107.13381767607669, +247.05062183657489], +[106.82014447371697, +247.43999190255605], +[106.50556357012113, +247.82862890550581], +[106.19005150491832, +248.21651033321879], +[105.8736648354778, +248.60367871771246], +[105.55645759807442, +248.99017511452669], +[105.2384482829486, +249.37601183534213], +[104.91964273178039, +249.7611909121002], +[104.60006820485283, +250.14573223561794], +[104.27984409080113, +250.52973282551483], +[103.9591221112567, +250.91331772514337], +[103.63806775911054, +251.29662450476815], +[103.3168941489707, +251.67983138189416], +[102.99583128140355, +252.063131045623], +[102.67505568284652, +252.44667113579129], +[102.35451781983456, +252.8304099402867], +[102.03408778298771, +253.21423879551753], +[101.71361846206025, +253.59803485318116], +[101.39291831495811, +253.9816380410841], +[101.0717803608276, +254.36487475813539], +[100.75004227476114, +254.7476077514217], +[100.42772837620342, +255.12985596821983], +[100.10492879546109, +255.51169414700217], +[99.781713126776353, +255.89318019509739], +[99.458046290899276, +256.27428352253389], +[99.133856284129308, +256.65494189217907], +[98.809134408093755, +257.03514664982157], +[98.484143217785586, +257.41512127662475], +[98.1592411906131, +257.79517215495656], +[97.834835918088174, +258.17564708449288], +[97.511506722094666, +258.5570366773469], +[97.189898002993459, +258.93987778958325], +[96.870515313337734, +259.32457750225529], +[96.553246810110124, +259.71102284210565], +[96.237755679618857, +260.09892085589485], +[95.923686815923887, +260.48797155642126], +[95.610695736336424, +260.87789002733882], +[95.298440675247789, +261.268398285932], +[94.986638508481334, +261.65926831629594], +[94.675251506898292, +262.05046917037134], +[94.364330286428313, +262.4420403126864], +[94.053894843843324, +262.833996685767], +[93.743808780650909, +263.22622954502276], +[93.433879010873369, +263.61858593266157], +[93.123977647604576, +264.01096476110024], +[92.814265251393962, +264.403492753118], +[92.5050072136382, +264.79637877759285], +[92.196505521941674, +265.18985889827786], +[91.889175783810245, +265.584254881594], +[91.58347760144126, +265.97991656046463], +[91.279782676848555, +266.37711766981579], +[90.97806998384867, +266.77582661993864], +[90.678172411974529, +267.17590277842351], +[90.379922461247574, +267.5772088273709], +[90.0832081723037, +267.97965169560325], +[89.787937680419091, +268.3831551169302], +[89.4940267722093, +268.78764997438708], +[89.201417962342859, +269.19308778603158], +[88.910063477295182, +269.599427936646], +[88.61992464417, +270.00663700629195], +[88.330997910950714, +270.4147069901606], +[88.043292866142238, +270.82363922470711], +[87.756793511406045, +271.23341708281362], +[87.47137269164331, +271.64394695945549], +[87.186861128380343, +272.05510756963037], +[86.903102477230533, +272.46678820322074], +[86.620011726932091, +272.87892842189308], +[86.337530421031289, +273.29148660656205], +[86.0555798646219, +273.70440771526887], +[85.7739883672951, +274.11757379717415], +[85.492549229421073, +274.53084369590556], +[85.211079711554319, +274.94409290656449], +[84.929509900172093, +275.35727378656924], +[84.647811820963454, +275.77036722587718], +[84.365884796676582, +276.183304441804], +[84.083312678218434, +276.59580041287126], +[83.799564380951139, +277.00748801191548], +[83.514088045728059, +277.41797893041672], +[83.226279496689727, +277.82683758583181], +[82.935520389547776, +278.23360264843171], +[82.641221215570312, +278.63781312297459], +[82.342894696826036, +279.03905975737734], +[82.040096942401448, +279.43694231692183], +[81.73231176775451, +279.83097853733506], +[81.418676956488227, +280.22037290632591], +[81.098232730686945, +280.60418062579117], +[80.770247873979727, +280.98156262841161], +[80.434831319054453, +281.35235544077972], +[80.092368999346718, +281.71665194111017], +[79.743207345160243, +282.07453344830606], +[79.387496261501752, +282.42590627422783], +[79.025321023353825, +282.77061259668341], +[78.656747023532773, +283.10846855039085], +[78.281767969567269, +283.43920120910479], +[77.900361765669359, +283.76250078669415], +[77.512511665850127, +284.07804088859149], +[77.118198499832516, +284.38546618506535], +[76.717411811183283, +284.68440292318991], +[76.310113685918353, +284.97440512370605], +[75.896121004284865, +285.25476669406527], +[75.47523719769481, +285.52467194950651], +[75.047357055261813, +285.78334215640149], +[74.612588218591867, +286.03025907916737], +[74.171116123374574, +286.2649815970878], +[73.723138995136452, +286.48703818571425], +[73.268839091670728, +286.69585490782572], +[72.808418531379985, +286.89080602916033], +[72.342164167513161, +287.07136148580469], +[71.87056136517748, +287.23744886732629], +[71.394130048290933, +287.38913363295995], +[70.9133799017745, +287.52652052643396], +[70.428829340589829, +287.64983894600005], +[69.940974779184174, +287.75936219842737], +[69.450284762636372, +287.85539019551084], +[68.957209843036736, +287.93831046621125], +[68.462167427169817, +288.00853970054658], +[67.965538282583978, +288.06649690668604], +[67.467665340548663, +288.11256454239725], +[66.968864394308255, +288.14716433770332], +[66.469419671652133, +288.17070791953807], +[65.9695868411607, +288.183604631433], +[65.4695948304111, +288.18626492713037], +[64.96964643762594, +288.17914721099521], +[64.469911344138254, +288.16290172226104], +[63.970521574798511, +288.13822409151237], +[63.471576805067592, +288.10576984335404], +[62.973157386865566, +288.06605474671466], +[62.47532447211227, +288.0195608646514], +[61.978105606726949, +287.96690263642159], +[61.481447312889784, +287.90919450669924], +[60.985247529352847, +287.847667223728], +[60.489395375116075, +287.78339805337583], +[59.993835078389367, +287.7169156428015], +[59.49852259349516, +287.64861127684378], +[59.003416985760957, +287.5788230963941], +[58.50850162385585, +287.50769825650349], +[58.013765598785987, +287.43533646167361], +[57.519196779216024, +287.36184052511646], +[57.024780564796522, +287.28732487006369], +[56.53050135471716, +287.21190575828035], +[56.036348034738047, +287.13566617388472], +[55.542327563604552, +287.05857046597941], +[55.048451564593144, +286.98055463756128], +[54.5547265749017, +286.90158875015572], +[54.061139694495665, +286.82176410290407], +[53.567672635225264, +286.74120201794415], +[53.074305840085472, +286.66002814032487], +[52.581016644293733, +286.57838399825039], +[52.087781279819623, +286.49641525855429], +[51.59457397436038, +286.41427785031914], +[51.101362631995094, +286.33216469494982], +[50.608113682100935, +286.25027777217889], +[50.114794308165983, +286.16881622125021], +[49.621373877604853, +286.08796908037721], +[49.127822863062534, +286.00792304314393], +[48.634111894135259, +285.92886964993244], +[48.1402100330086, +285.85101788609313], +[47.646087111312362, +285.77458186176551], +[47.151710610865052, +285.699803700381], +[46.657035509355396, +285.62702729518378], +[46.162017504292642, +285.5566213169713], +[45.666623760242835, +285.48890977459575], +[45.170848517456072, +285.42405056197362], +[44.674693928417511, +285.36216009240019], +[44.178166256002214, +285.30333761200325], +[43.6812808397168, +285.24761771723985], +[43.184055315124247, +285.19501913966019], +[42.68650626185331, +285.1455744543124], +[42.188645988616855, +285.09936849857297], +[41.690487266654522, +285.05649970041696], +[41.1920429917952, +285.01708968632778], +[40.693322229052995, +284.98134834134811], +[40.194337222353937, +284.94950796301691], +[39.695107951080253, +284.92175912841941], +[39.195666816453077, +284.89812792827564], +[38.696048424412986, +284.87859958582283], +[38.196285844001942, +284.8631962910236], +[37.696409424179222, +284.85208482383695], +[37.196453305000716, +284.84546801231755], +[36.696457425209559, +284.8434588712222], +[36.196463044815559, +284.84581449017077], +[35.696503919013232, +284.85220295099509], +[35.196605471201025, +284.86227730114416], +[34.696783898746169, +284.87563229894306], +[34.197046926102352, +284.89184739292097], +[33.697391601577571, +284.910409299547], +[33.1977930733262, +284.93044199732111], +[32.698214959641142, +284.95097746867987], +[32.198610169884759, +284.97085225590172], +[31.698909331520113, +284.98814103618224], +[31.199068128544958, +285.0007267308406], +[30.699104615076251, +285.00672251453744], +[30.199107842400462, +285.0051377127142], +[29.699207436476978, +284.99520620298796], +[29.199572133505718, +284.97614528579805], +[28.700418246010258, +284.94709751536362], +[28.202015549166536, +284.90718901056727], +[27.704681084493725, +284.85565250606891], +[27.208739028916838, +284.79210183749154], +[26.714529585177537, +284.716247851077], +[26.222409953723481, +284.62784693142169], +[25.732729621560608, +284.52680602128777], +[25.245841054716344, +284.41307285837973], +[24.762101963585764, +284.28661407202958], +[24.281862401933278, +284.14745622582154], +[23.805472725600648, +283.99564239251714], +[23.333271188372741, +283.83126466109144], +[22.865535346990438, +283.65458041051437], +[22.402514849919861, +283.465884907217], +[21.944440917767857, +283.26548005277704], +[21.491508984156731, +283.05371040030622], +[21.043893207623011, +282.83092407682761], +[20.60175163461761, +282.59746231367853], +[20.165227213322506, +282.3536592224807], +[19.734448307981015, +282.09984231924727], +[19.309528784477013, +281.83633355004093], +[18.890563286950869, +281.56345740916464], +[18.477633229597764, +281.28153149685693], +[18.070832110931821, +280.99083216436821], +[17.67031936401899, +280.69152873040287], +[17.276269617052279, +280.38376644570371], +[16.888816851762353, +280.067739102077], +[16.507961912937937, +279.74379060747208], +[16.133660919180951, +279.412290856404], +[15.765847619969941, +279.07360667010715], +[15.4044162516313, +278.72811966296092], +[15.04924291108037, +278.37620201423135], +[14.700247639480429, +278.01815687770778], +[14.357510910868687, +277.65411656382565], +[14.021154579498308, +277.28417329970989], +[13.691305583405574, +276.90841674441083], +[13.368103222127932, +276.526928454621], +[13.051690760021515, +276.13979025902256], +[12.74219704782759, +275.74709913960874], +[12.439706029837412, +275.3489889477475], +[12.144290275619596, +274.94560089125446], +[11.856029902445481, +274.5370691977605], +[11.575028463215943, +274.12351127551057], +[11.30139834652509, +273.70503996475355], +[11.035287781499973, +273.28174772724873], +[10.77694232331022, +272.85367278102422], +[10.52662969545854, +272.4208522685679], +[10.284553337108379, +271.9833719983348], +[10.050737527986076, +271.541421562056], +[9.8251700625751131, +271.09520498721025], +[9.6079452523820041, +270.64486908562668], +[9.3994396370098254, +270.19043171421885], +[9.2000927381145541, +269.73190386776491], +[9.0102210214524447, +269.2693719951385], +[8.8298153991997612, +268.80306619974982], +[8.6587830185494656, +268.33324118609636], +[8.4969968632234725, +267.8601519595062], +[8.3442494834181744, +267.38406686086643], +[8.2003075350064147, +266.90524525938821], +[8.0649159828432513, +266.42393531692], +[7.9377719677754728, +265.940380497485], +[7.8185306959479446, +265.45481540085541], +[7.7065885839961865, +264.96751340976738], +[7.6007318497301535, +264.47885114065366], +[7.499619243598163, +263.98918367727981], +[7.4021258553463891, +263.49878216247646], +[7.3076401737446384, +263.00779187262162], +[7.215698299511228, +262.51631864416851], +[7.126078025156251, +262.02441700048462], +[7.0391123057555136, +261.53203951081713], +[6.9552531829816, +261.03912380125013], +[6.874834879322993, +260.54563514145457], +[6.7979224930922184, +260.05158793930951], +[6.7244995183709424, +259.55701002046806], +[6.6543928342639243, +259.06195064966482], +[6.5870785368350617, +258.56650338915119], +[6.5219598927036042, +258.0707624303223], +[6.45853484680252, +257.57480180182841], +[6.3965133696087006, +257.07866360107107], +[6.3356730802184718, +256.58237911947288], +[6.2759405909207091, +256.08596017288744], +[6.2175728302356585, +255.58937906748102], +[6.1608923649808069, +255.0926026898378], +[6.1061152530051075, +254.59561283479877], +[6.0532217451546115, +254.09841894159925], +[6.0021211889639128, +253.60103749124048], +[5.9525964383306809, +253.10349645457259], +[5.9041520206898177, +252.60584891010967], +[5.8562382383391718, +252.10814993778951], +[5.8084028910656986, +251.61044342067447], +[5.76040825228118, +251.11275225163212], +[5.712074208807798, +250.61509394771477], +[5.663278125038306, +250.11748073552712], +[5.6140236309760976, +249.61991268374481], +[5.5643402316695632, +249.12238727454763], +[5.5142246341402235, +248.62490522478745], +[5.4636015222325884, +248.12747457816067], +[5.4123749518856945, +247.63010573701558], +[5.3604187276877768, +247.13281263394927], +[5.3075401733642291, +246.63561682291621], +[5.2535391830148015, +246.13854172876742], +[5.1982836799615866, +245.64160452054136], +[5.1417907936559946, +245.14480643984069], +[5.0841222624243567, +244.64814341941008], +[5.0254182389867417, +244.1516016374722], +[4.965991210843784, +243.65514579968431], +[4.9061878892644026, +243.15873512231764], +[4.8463018297486791, +242.66233441804803], +[4.78650992199473, +242.16592237086871], +[4.726962804864538, +241.66948091463877], +[4.6678219325095105, +241.17299092535214], +[4.6092724930219475, +240.67643088171241], +[4.5515000901365266, +240.17977987592107], +[4.4946464878567038, +239.68302286754823], +[4.4387569772593416, +239.18615647375475], +[4.3838448311872611, +238.68918110735805], +[4.3298464871946587, +238.19210556416442], +[4.2765298062178276, +237.69495639279262], +[4.2236323750466607, +237.19776241371164], +[4.1709719966342549, +236.7005432701134], +[4.1185422051966842, +236.2032997618121], +[4.0663870998180416, +235.70602737486649], +[4.0146257606592952, +235.20871388740181], +[3.9635408957851745, +234.71133053444447], +[3.9134457286666868, +234.21384662139366], +[3.8645859528675133, +233.71623989994026], +[3.8170601399341884, +233.21850402953427], +[3.7709248181192638, +232.72063736049239], +[3.7261760136755697, +232.2226441012829], +[3.6826785456892654, +231.72453992107668], +[3.6402729108956526, +231.22634155750714], +[3.5988543590948097, +230.7280601625551], +[3.5584366533201308, +230.22969659989025], +[3.5190713318483615, +229.73124883791388], +[3.4808901125340537, +229.23270909438378], +[3.4441975535791207, +228.73405774982729], +[3.4093245895864888, +228.23527601369204], +[3.37648418990102, +227.73635631237198], +[3.3456352897201569, +227.23730945326588], +[3.31666138283632, +226.73815012174043], +[3.2893198999250388, +226.23889847987218], +[3.263098313576839, +225.73958659362802], +[3.2374378579818179, +225.24024549133853], +[3.2119205634083965, +224.74089704838588], +[3.186429431973401, +224.24154726897325], +[3.1609290109332369, +223.74219796385179], +[3.1354699325765782, +223.24284655694595], +[3.1102863752273668, +222.74348121085029], +[3.0856465016420072, +222.24408878827487], +[3.0617448808332766, +221.74466049886649], +[3.0386194246455878, +221.24519566852911], +[3.0162678006611916, +220.74569560617971], +[2.9946606636939515, +220.24616276617434], +[2.9737111957180042, +219.74660189243988], +[2.9533178164120386, +219.24701799084241], +[2.9333689446781395, +218.7474161251393], +[2.9137316224357255, +218.24780190481061], +[2.8942692310442624, +217.74818083384611], +[2.87485588419756, +217.24855785421781], +[2.8553886181228343, +216.74893697516976], +[2.8357623363679636, +216.24932232598641], +[2.8158107116270106, +215.74972060122235], +[2.7952353969257295, +215.25014424822689], +[2.773697244499985, +214.75060860764705], +[2.7507764666411734, +214.25113478212893], +[2.7258775187119233, +213.75175608708957], +[2.6983703264862164, +213.25251478264397], +[2.6676769106125495, +212.75345970651867], +[2.633332530539787, +212.25464307821076], +[2.594905657474627, +211.75612482977772], +[2.5520128266380588, +211.25797132665045], +[2.5043755540490684, +210.76024944769404], +[2.4517347395219726, +210.26303226183933], +[2.3937769991113615, +209.76640740771296], +[2.3300601087922419, +209.27048929866726], +[2.2601057421142983, +208.7754134024014], +[2.1833644279043463, +208.2813453621649], +[2.0991115305442469, +207.78850419198093], +[2.0065867476633485, +207.29715036021707], +[1.9050499577058329, +206.80758096976808], +[1.7937932072798495, +206.32013012883476], +[1.672121238781922, +205.83517578067429], +[1.539318103183771, +205.35315268415175], +[1.39458059217181, +204.87457970368351], +[1.2371066311318277, +204.40004699640065], +[1.0661740874984689, +203.93019557622014], +[0.88121972041128249, +203.46568571101477], +[0.68173925008102632, +203.00722683242304], +[0.46727956567923445, +202.55558083327651], +[0.23744266162336064, +202.11156225684826], +[-0.0081234320433649348, +201.6760446113187], +[-0.26974730554413923, +201.24997870548012], +[-0.54773883759970221, +200.83440546434647], +[-0.84237497879361267, +200.43045979851979], +[-1.1535797929113627, +200.03913063520682], +[-1.4802157657088721, +199.6605806144789], +[-1.8209552174852437, +199.29466918808487], +[-2.17473838897874, +198.94134935235618], +[-2.5413015759771307, +198.60130313500093], +[-2.9205839261168776, +198.27550493058271], +[-3.3121512667495097, +197.96458449839105], +[-3.7150507950631084, +197.6684998282048], +[-4.1282379790781283, +197.38695263509987], +[-4.5509124062058017, +197.11986232928305], +[-4.9830029124500541, +196.86829491256228], +[-5.4245237233533272, +196.63367931762303], +[-5.8750720898845561, +196.41691019290985], +[-6.3331075011777109, +196.21643886805481], +[-6.7969931950198, +196.02989449521164], +[-7.2652870265854261, +195.85470011087759], +[-7.7365971690171884, +195.68777975404024], +[-8.20965636275874, +195.52587428321635], +[-8.6834989409895229, +195.36627202039713], +[-9.15801061280413, +195.20867004241688], +[-9.6333321308300732, +195.05352817144845], +[-10.109445701535337, +194.90083425133491], +[-10.585667792361217, +194.74847770265998], +[-11.06110180557789, +194.59368111904644], +[-11.534854214401134, +194.43381683955002], +[-12.006209714082896, +194.2670229522956], +[-12.474458686334167, +194.09170281648963], +[-12.938736403147866, +193.9061286200122], +[-13.397720829674743, +193.70783553207059], +[-13.849749084630123, +193.4941743492829], +[-14.293111607570179, +193.26307967660964], +[-14.72699564458382, +193.01464525338346], +[-15.150939003990745, +192.74960073344218], +[-15.564529700035079, +192.46867226484628], +[-15.96734897437142, +192.17250326681406], +[-16.359000572452182, +191.86171426955448], +[-16.739027816808203, +191.5368126878858], +[-17.106586479291437, +191.19787000041845], +[-17.460652274208993, +190.84485659786984], +[-17.800330516109547, +190.47797787400577], +[-18.12558270743914, +190.09824818500329], +[-18.436700655357061, +189.70685089018374], +[-18.733856184939025, +189.30474799578533], +[-19.0164133311995, +188.89225544211374], +[-19.28346242367823, +188.46955729503142], +[-19.534245152503114, +188.03700941282716], +[-19.768737308887378, +187.5954156609686], +[-19.987166313019497, +187.14565761576961], +[-20.189859923386567, +186.68859027539756], +[-20.377466454653717, +186.22512431637242], +[-20.550758362927411, +185.75611666834888], +[-20.710519536310553, +185.28232803474467], +[-20.857473583972777, +184.80441167695224], +[-20.99241367340181, +184.32296548596702], +[-21.115907495213527, +183.83845744277744], +[-21.227739098905086, +183.3511260333706], +[-21.327486527993749, +182.86117899742959], +[-21.414802911787177, +182.36886506403377], +[-21.48964440256324, +181.87450133513408], +[-21.55203928392789, +181.37841339993824], +[-21.602004167351012, +180.88092014357551], +[-21.639500560062046, +180.38233240733783], +[-21.664480963985135, +179.88296136847103], +[-21.676972693498605, +179.38312202201215], +[-21.677275401432276, +178.88312665126614], +[-21.665755164034454, +178.38326383320324], +[-21.642799175963926, +177.88379537694848], +[-21.608881689072206, +177.38495119173484], +[-21.564496789849308, +176.88692897956327], +[-21.510148030493458, +176.38989516304156], +[-21.446386148937393, +175.89398075188785], +[-21.373771555230554, +175.39928476912434], +[-21.292907208303159, +174.90586975367773], +[-21.204554043461929, +174.41374012026728], +[-21.109503676743429, +173.92285962963339], +[-21.008457748765625, +173.43317796233882], +[-20.901836878531835, +172.94467970315452], +[-20.78999205164142, +172.45735081339697], +[-20.673292586603008, +171.97116141531248], +[-20.552174698071774, +171.48605365719584], +[-20.427085003642702, +171.0019547043994], +[-20.298398420955092, +170.51879941321965], +[-20.166266420169308, +170.03657495634883], +[-20.030788511874377, +169.55527975541705], +[-19.8921219031503, +169.07489342752791], +[-19.750607827421, +168.59533806585063], +[-19.606624213013166, +168.11651828802349], +[-19.46042644839082, +167.63836995432851], +[-19.311891547677959, +167.16094256344178], +[-19.16080885846333, +166.68431537317556], +[-19.007036290319988, +166.208549182991], +[-18.850640127557014, +165.73363893255981], +[-18.691729685838375, +165.25956407020271], +[-18.530296174033868, +164.78634260061233], +[-18.365973510342194, +164.31411685247852], +[-18.198310222507761, +163.84306714702072], +[-18.026843595604618, +163.37338893101216], +[-17.851070777164491, +162.90530570261106], +[-17.670491164701847, +162.43905621212647], +[-17.484730646688821, +161.97484662496981], +[-17.293775509413528, +161.51274959510735], +[-17.097699960935287, +161.05280183702837], +[-16.89659275226245, +160.59503166335506], +[-16.690585296273465, +160.13944559865854], +[-16.479818429947496, +159.68604163399698], +[-16.264429998182671, +159.2348147068661], +[-16.044552284885867, +158.785758144287], +[-15.820311773350902, +158.33886413449687], +[-15.591788526728562, +157.89414498777739], +[-15.358932567080007, +157.45167917604746], +[-15.121680116211079, +157.01155506409432], +[-14.880189370495652, +156.5737413629796], +[-14.635254968646299, +156.13784413962574], +[-14.387803546228739, +155.70337039215275], +[-14.138595977956056, +155.269901424166], +[-13.887934351774208, +154.83727159756529], +[-13.636029242658351, +154.40536450914172], +[-13.38337150132377, +153.97389719251174], +[-13.131279262427622, +153.54209967319682], +[-12.881268416288972, +153.10909461458692], +[-12.634777865188449, +152.67407701206633], +[-12.392998827411011, +152.23642442375984], +[-12.157073177033659, +151.79559011973555], +[-11.928112752794826, +151.35109939345762], +[-11.707107943491479, +150.90260086446924], +[-11.495034735356016, +150.44981146478329], +[-11.292922349191462, +149.9924898014944], +[-11.101938319949088, +149.53041078158583], +[-10.923307132733482, +149.06341752763362], +[-10.758096730063134, +148.59150823249553], +[-10.606748967539236, +148.11497057325539], +[-10.469544323902761, +147.63416840483467], +[-10.346866975143474, +147.14945424355963], +[-10.239518914856726, +146.66111404874903], +[-10.14856987992655, +146.16945535306138], +[-10.074651172821463, +145.67495201098907], +[-10.01769946196332, +145.17821117226802], +[-9.9774646188758069, +144.67984006083387], +[-9.95367248508991, +144.18041600691637], +[-9.9459222065694473, +143.6804875385489], +[-9.9537810076580175, +143.1805623795712], +[-9.97691097601687, +142.68111233397912], +[-10.015338389589417, +142.1826082380208], +[-10.069202790777664, +141.68553781173932], +[-10.138716489910092, +141.19041633628626], +[-10.224396415297731, +140.69783916901574], +[-10.32685334318022, +140.20848140956329], +[-10.446625118976629, +139.72307634485009], +[-10.583947556145503, +139.24234597113693], +[-10.738948605095986, +138.76702532796182], +[-10.911740454565635, +138.29788393684123], +[-11.102415260277839, +137.83572701748571], +[-11.311058723636776, +137.38140472204333], +[-11.53771944392102, +136.93580339961503], +[-11.782371099998507, +136.49982605321608], +[-12.044942569693717, +136.07440659380359], +[-12.325248604773275, +135.66046269733], +[-12.622691377248076, +135.25865617112129], +[-12.936496440732888, +134.86949317405424], +[-13.265920515003804, +134.49345924333929], +[-13.610348189791752, +134.13111978830909], +[-13.969232285240125, +133.78309584117812], +[-14.342071483040101, +133.45006937083807], +[-14.728544995642423, +133.13297699006898], +[-15.128392562261229, +132.83293779269405], +[-15.541144647958632, +132.55092281330215], +[-15.965716835606379, +132.28702258643992], +[-16.400735772796107, +132.04070217700826], +[-16.84484331405887, +131.81114845102866], +[-17.296538830605577, +131.59687250212011], +[-17.754329015294243, +131.3959073079665], +[-18.216900515785753, +131.20617205018345], +[-18.683154022998963, +131.02564692810046], +[-19.152149154957868, +130.85234703184852], +[-19.623037683766306, +130.68424307853678], +[-20.095022748920506, +130.51923190805093], +[-20.567333019676912, +130.35514963255241], +[-21.039206846114332, +130.18981904114335], +[-21.509862521854018, +130.02106121916543], +[-21.978470537575962, +129.84671360642272], +[-22.444136055686439, +129.6646732733906], +[-22.905911847486667, +129.47300384418165], +[-23.362753387821723, +129.26988055520894], +[-23.813439656744166, +129.05347443422747], +[-24.256420243606083, +128.82174517577135], +[-24.689771160310165, +128.57252027912597], +[-25.111435272675159, +128.30403748696745], +[-25.520111318478076, +128.01617122075706], +[-25.915100108775231, +127.70978517186236], +[-26.2957822299131, +127.38578992938244], +[-26.661043919419377, +127.04451310217621], +[-27.009413564957065, +126.68602241605622], +[-27.339422663097629, +126.31057004570548], +[-27.650345848678775, +125.91915880779851], +[-27.941922917752663, +125.51312085732287], +[-28.214038830873225, +125.09378272753642], +[-28.46683382083102, +124.66251109556168], +[-28.700630946204036, +124.22064167638598], +[-28.9156182583475, +123.76931521721221], +[-29.11085972813143, +123.30911037028766], +[-29.28474485675542, +122.84043133943212], +[-29.435724915071283, +122.36389032214622], +[-29.563169600802578, +121.8805217719561], +[-29.666975382415643, +121.39152829491864], +[-29.747088135319057, +120.89809736471206], +[-29.803397331839278, +120.40138658689386], +[-29.835743127524946, +119.90254241667239], +[-29.84401485373834, +119.40271970273375], +[-29.82827976165369, +118.90307515236893], +[-29.788710124443995, +118.40475058812928], +[-29.7256289535054, +117.9088514741626], +[-29.64001559620035, +117.41633322213494], +[-29.533189825576333, +116.9279667947647], +[-29.406535925068173, +116.44435371680291], +[-29.261583654321509, +115.96589544205938], +[-29.099951993231258, +115.49280051650436], +[-28.92320522613549, +115.02513272118824], +[-28.732779655414479, +114.56285759643862], +[-28.530034032693344, +114.1058442598472], +[-28.316350042683304, +113.65383461458144], +[-28.093355947321889, +113.20633638283371], +[-27.86279985361535, +112.76267946647044], +[-27.626299894847747, +112.32215693565041], +[-27.384973288022998, +111.88425722268359], +[-27.139661465911576, +111.44857562390153], +[-26.891156004462335, +111.01470613998515], +[-26.640236365582982, +110.58222716559038], +[-26.387673091737817, +110.15070515034007], +[-26.134355236329924, +109.71962511506889], +[-25.881710261963466, +109.28815066876513], +[-25.6314760979607, +108.85527576331694], +[-25.385079258827751, +108.42020787368521], +[-25.142321160266754, +107.98309750622641], +[-24.902072781569181, +107.5446006217625], +[-24.66323038034648, +107.10533534302697], +[-24.425441327857989, +106.66549889567369], +[-24.18877707808484, +106.22505628517496], +[-23.953323586533507, +105.78396528209137], +[-23.71895439303217, +105.34229706547494], +[-23.4854229398439, +104.90018518761427], +[-23.252496923744872, +104.4577539545341], +[-23.020085803590256, +104.01505201476101], +[-22.788179176564398, +103.5720855915196], +[-22.556824581827893, +103.12883062012148], +[-22.326270416480277, +102.68515891911765], +[-22.096879939025161, +102.2408846765792], +[-21.869024193658635, +101.79582166647715], +[-21.643029203076772, +101.3498112328416], +[-21.419196018521202, +100.902712324407], +[-21.197825690991145, +100.45438929074945], +[-20.979230341145307, +100.0047071704695], +[-20.763729968999, +99.553534208984217], +[-20.551658639039587, +99.1007399527807], +[-20.343399556481437, +98.6461804913428], +[-20.139367566484474, +98.189708977206692], +[-19.939974971803888, +97.731192909285454], +[-19.745585100713967, +97.2705345210224], +[-19.556534113345379, +96.8076603872712], +[-19.373221683015423, +96.342485000069587], +[-19.196341182109684, +95.874828653833134], +[-19.026774773410715, +95.4044741977892], +[-18.865282103442294, +94.931289598284351], +[-18.711890174618638, +94.455416073863375], +[-18.56616104028079, +93.977138226183484], +[-18.427697746030422, +93.496705246415345], +[-18.29664867467935, +93.014198419058516], +[-18.173515293919415, +92.529613147672137], +[-18.058670830387197, +92.042997847832027], +[-17.951635445938003, +91.554602190509272], +[-17.851365442839015, +91.064769037532969], +[-17.756740473296407, +90.573811082549426], +[-17.666736020531008, +90.081982896705881], +[-17.580389745170702, +89.589497606151724], +[-17.496842712031796, +89.096528612438831], +[-17.415670409213618, +88.603162773901374], +[-17.336737331907788, +88.109433644075409], +[-17.259963190258489, +87.615364121662438], +[-17.185299854138179, +87.120971178491175], +[-17.112720420403114, +86.626267989139563], +[-17.042067124380111, +86.131285833940026], +[-16.972576746811583, +85.636138445938], +[-16.90308070612409, +85.140991739816528], +[-16.832262934815944, +84.646033024909585], +[-16.758449141906013, +84.151514500558676], +[-16.679726615222769, +83.6577577356662], +[-16.594404048977559, +83.165103166395937], +[-16.501961926821558, +82.6737347934183], +[-16.402657815301158, +82.183705905408544], +[-16.29679326563609, +81.695051555905479], +[-16.184288706772374, +81.207883896954129], +[-16.064816125673055, +80.722379315312665], +[-15.937984905334, +80.238746361799684], +[-15.803293868589837, +79.757245315699535], +[-15.660171849906572, +79.278185137820174], +[-15.508048561293407, +78.8019094208122], +[-15.346384331651683, +78.328789824015615], +[-15.174660747793784, +77.859230698064977], +[-14.992397145284293, +77.393664329212029], +[-14.799240743394478, +76.9325129602954], +[-14.594917974192022, +76.476201418755622], +[-14.379164260310503, +76.025184606521051], +[-14.151642537050719, +75.579991661988487], +[-13.911983843711525, +75.141216888020622], +[-13.659951894483648, +74.709433150346825], +[-13.395858008662341, +74.284916916088719], +[-13.120324825708247, +73.867730662471573], +[-12.833980954518097, +73.457885583045964], +[-12.537354958961863, +73.055417091814377], +[-12.230909091620706, +72.660372002338008], +[-11.91508357471384, +72.272782450196871], +[-11.590293384271842, +71.892671482765152], +[-11.25693787282923, +71.520047520748449], +[-10.915403261993912, +71.154903634853255], +[-10.566060802034528, +70.797220564615131], +[-10.20927134949982, +70.44696361211075], +[-9.8454281234507377, +70.1040374387496], +[-9.4751029705583854, +69.768117215789289], +[-9.0989516379718935, +69.438729605161], +[-8.7175777940822847, +69.115399442719593], +[-8.3314062917595848, +68.7978127830651], +[-7.9407597208189173, +68.485745470838566], +[-7.5458425751041931, +68.179099669217948], +[-7.14644591021051, +67.878314461731222], +[-6.7421610938998811, +67.5841365059542], +[-6.3326368925238317, +67.297301326442209], +[-5.91777784533921, +67.018239273117516], +[-5.4976243953223687, +66.747214752403238], +[-5.0723140948454457, +66.484356362416378], +[-4.642297140053822, +66.229265455420844], +[-4.2081548291404962, +65.98125484471997], +[-3.7704148243816538, +65.739646160812185], +[-3.3294176814817238, +65.504032763281643], +[-2.8854072951507845, +65.274146436146708], +[-2.4385643599867985, +65.049814466307481], +[-1.9888859543815069, +64.8312229833371], +[-1.5362894870362018, +64.618741199215279], +[-1.080722032592397, +64.41270796317626], +[-0.62225615383610355, +64.213207167893387], +[-0.16102099403342512, +64.020194276787265], +[0.30284417117668055, +63.833589568860909], +[0.76917541619379648, +63.653234559594239], +[1.2378029690362666, +63.478931515351228], +[1.7085620853839183, +63.310468614923408], +[2.1812884644487034, +63.1476059301152], +[2.6558231663045739, +62.990088098991478], +[3.1320125253942641, +62.837643680633278], +[3.6096971129712134, +62.68994921605718], +[4.0887205232904, +62.54665449625783], +[4.5689427367371689, +62.407428349800419], +[5.0502619597553018, +62.272042264515065], +[5.5325955317443816, +62.140314709415108], +[6.0158742787475239, +62.012097477661733], +[6.5000638709772467, +61.887363924902658], +[6.9851448445613347, +61.766143290211417], +[7.4710878144121926, +61.64842557948726], +[7.9578180229635569, +61.534005242910325], +[8.4452444228550334, +61.422586551493062], +[8.9332796683580078, +61.313864453250659], +[9.4218437667388688, +61.207542996195215], +[9.9108621948900755, +61.103330176837773], +[10.400256273156437, +61.000894959771294], +[10.889916925835545, +60.89974049607234], +[11.379723657455409, +60.79929494458365], +[11.869559781049315, +60.698992542910389], +[12.359322402629882, +60.598332009778339], +[12.848913655119834, +60.4968417471379], +[13.33822828536888, +60.3940269830709], +[13.827131578320078, +60.289275367741638], +[14.315469515287759, +60.181921398314415], +[14.803084880066312, +60.071334499451424], +[15.289850049730935, +59.957065524614], +[15.775649018304089, +59.83875815573586], +[16.26032598371371, +59.715947115248994], +[16.742612593631673, +59.584073272463456], +[17.2229718729676, +59.445353189001182], +[17.701824534840245, +59.301492489278644], +[18.179979844833028, +59.155317894114532], +[18.923648729985622, +58.929820042522763]], +"RacingPsi":[4.4228921582226617, +4.4160546489755754, +4.4090749357815362, +4.4016651814071972, +4.3934876575712254, +4.38428277080816, +4.3738312516155187, +4.3597470457047356, +4.3481820448592234, +4.3390962484266673, +4.3323697869266331, +4.3277320642197887, +4.3248843152460683, +4.32356318524076, +4.323647257781837, +4.3250498190882851, +4.3276762514840312, +4.3313972998357668, +4.33607480239207, +4.3416018548094639, +4.3480016761806093, +4.3553298516756582, +4.3636408453072892, +4.3729818989672689, +4.3833993793984751, +4.394908935690311, +4.4074241171373405, +4.4208297595878223, +4.4349987660657959, +4.4497490722431667, +4.4648874723871046, +4.4802369864788281, +4.4956815068801612, +4.51111939175753, +4.526371086135299, +4.540967562021085, +4.5543669733680421, +4.5660635859982728, +4.5756727716632133, +4.5828465045236939, +4.5873211409253711, +4.5891520415840974, +4.5884755335483423, +4.5854927436251192, +4.5806455971257245, +4.5744350523706041, +4.5673448541593329, +4.55978919463438, +4.5521646731480176, +4.5447521088768879, +4.537408092982119, +4.529889355252064, +4.522149537094406, +4.5148586661834011, +4.5088578529477585, +4.50494680821518, +4.5037853257574856, +4.5059981491240659, +4.5121742217286167, +4.5228193651874022, +4.5384074546887039, +4.5591884649351755, +4.5848230769843044, +4.6148037032423845, +4.648602231634217, +4.6852007544527945, +4.7235572394549621, +4.7626565960713494, +4.8018814854452847, +4.8406458602629154, +4.8783067405781422, +4.9141070478434417, +4.94722016392606, +4.9770494702370085, +5.0035642690700435, +5.0269625728193361, +5.047451965676288, +5.0652984275556268, +5.0807867311746469, +5.0942404210234651, +5.106091675004083, +5.1167969385869831, +5.1267603477215751, +5.1362222661301029, +5.1453812827750305, +5.1543748269474934, +5.16314853774393, +5.1716018459312014, +5.1796541382018342, +5.1872867965772738, +5.1944958826737251, +5.2012757579014188, +5.2076145214807239, +5.2134992708804031, +5.2189164768402438, +5.223849829067456, +5.2282823343435023, +5.2321913425772708, +5.235536968905, +5.2382741325839675, +5.2403423296020941, +5.2416335797607241, +5.2420293449789712, +5.2414294601838849, +5.2397906267023489, +5.2370841370785541, +5.2332937524177012, +5.2284424693938911, +5.2225641134290335, +5.2157156598137115, +5.20802607670338, +5.1996401321459382, +5.1906581917165457, +5.1810328073467842, +5.1706829530215161, +5.1595676890397089, +5.1477789070707214, +5.1354419026280258, +5.1226932376510437, +5.1097130633104957, +5.0966912814769758, +5.0838433439169934, +5.0714631025557795, +5.0598655193077287, +5.0493515943367173, +5.0401831579344218, +5.0326078724167633, +5.0268471276104449, +5.0230348855226543, +5.0212875931940184, +5.021821700532735, +5.0251963118653951, +5.0320510717601383, +5.0428724073091722, +5.0576063438336858, +5.0760723765764384, +5.0980629457261326, +5.1233620898173218, +5.1517290328132477, +5.1828310746637261, +5.216096980163627, +5.2508820071877516, +5.2866388747706816, +5.3231925656601531, +5.3604437391302335, +5.3983099385456095, +5.4367998763002632, +5.4759457811907648, +5.5157469248959643, +5.555935414736993, +5.5962215024187136, +5.6364159059209564, +5.6768431346035673, +5.7178690615811032, +5.75978694834784, +5.8031357474460084, +5.8483798671732838, +5.8958005295039912, +5.9442766719353726, +5.9926157964608162, +6.0395754727378224, +6.0835968856451084, +6.1232178778903021, +6.157316698662008, +6.1860929935865014, +6.2098336788210675, +6.229171734497803, +6.2455588826104274, +6.26069218526219, +6.2761070833161865, +6.2928660923324715, +6.3119210416827558, +6.3337568561853592, +6.3578236934210475, +6.38329059195758, +6.4093923132618436, +6.4355514419056581, +6.4612329061393439, +6.4860476026554039, +6.5099268919050974, +6.5328971263561835, +6.5549249041014619, +6.5758185204593609, +6.5953649088832158, +6.6134431714393624, +6.6301499552383083, +6.6456368337711957, +6.6600843567425159, +6.6737503976016157, +6.6869054038713776, +6.6998025194652007, +6.7126477776841043, +6.7256290152268763, +6.73883867137244, +6.7521465650117172, +6.7653730451581762, +6.7783357876667658, +6.790853456670761, +6.8027533924053021, +6.813965383726166, +6.8246459759625475, +6.8350016921149868, +6.8452224571591529, +6.855457824820772, +6.8658417349842553, +6.8764356797654509, +6.8871444680943, +6.8978327325816711, +6.9083313163095372, +6.9184015172270863, +6.9277926630632329, +6.9363005643480182, +6.9438175443244479, +6.9502663963344862, +6.9556248767585256, +6.9599862160340926, +6.963472197461992, +6.9662131869418396, +6.9683576186738749, +6.9700575043809732, +6.9714604304440373, +6.9727048352016148, +6.9739203597478312, +6.9751848571328434, +6.9764689545275917, +6.97771751479738, +6.9788702715735242, +6.9798563561441718, +6.9806036070701012, +6.9810492510292326, +6.9811499114541835, +6.98087133119418, +6.9802149697060578, +6.9792561368351578, +6.9780843016510818, +6.9767644737950461, +6.9753112391208028, +6.973733518271418, +6.9720877535983252, +6.970528004965602, +6.9692302907839849, +6.9683632877286046, +6.9680805845302505, +6.9685274687167054, +6.9698121508881279, +6.9719669868283782, +6.975002471787386, +6.97889733278656, +6.9835660028654685, +6.9889047213219007, +6.9947866144795681, +7.0010386690617565, +7.007483349028143, +7.0139926082040081, +7.0205379173856, +7.0271125347652932, +7.0336987903324886, +7.0402570636384167, +7.0467437817705756, +7.0531233193082219, +7.0593757190219684, +7.0654820010785073, +7.0714026617338455, +7.0770576647996215, +7.08235947635914, +7.0872343932520323, +7.0916355340603561, +7.0955203005031731, +7.0988294530416454, +7.1014709850625266, +7.10334948566716, +7.1044003629811243, +7.1046196741531977, +7.1040153020146395, +7.1025785399920238, +7.1002679014736465, +7.0970382544889361, +7.0928741674563671, +7.0878196992065554, +7.0819288332195436, +7.0752248900455843, +7.0676675843200094, +7.0592004166495075, +7.0497470288709927, +7.0391813810669506, +7.0273762202138919, +7.0142668940110395, +6.9999289863181708, +6.9844728615360143, +6.9680510149849457, +6.9509146715313861, +6.9333339271482064, +6.91556030055556, +6.8977858329459005, +6.8801870950874129, +6.8628478506624013, +6.8456234874940849, +6.8283198023290126, +6.81075284368517, +6.7927787668812609, +6.7742611084166766, +6.755116012308207, +6.7353980592208318, +6.7151953498020145, +6.6946089743828772, +6.6737576535790986, +6.6527697893381017, +6.6317417724513517, +6.6106742466808219, +6.5895454748325974, +6.5683268808961719, +6.5469757670091608, +6.5254435580828583, +6.5036869117422889, +6.4816575849098257, +6.4593130007968318, +6.4366237545013947, +6.4135968360380788, +6.3902501408600623, +6.3666170493818468, +6.3428575513184606, +6.3191450365001485, +6.29563907383798, +6.2724334988687929, +6.2496057695919376, +6.2272004525406111, +6.2050089573463305, +6.1827904908044227, +6.1602871254024487, +6.1371886741238777, +6.1131628372206581, +6.0879307800475706, +6.0615747212812989, +6.0342502926599488, +6.0061693265092613, +5.97766123396926, +5.9491143427154736, +5.9208906906226382, +5.893111400038852, +5.8658509793699967, +5.8391451868591773, +5.8129287014373983, +5.787087350741408, +5.7615071055309306, +5.7361878330797769, +5.711142438029035, +5.6864210544842919, +5.6622749647501207, +5.6390272801445427, +5.6169594529063263, +5.596060584321159, +5.5762249052478641, +5.55730688412767, +5.5390424985411766, +5.5211128517727932, +5.5032168057194779, +5.485216353307754, +5.4670314376066829, +5.4486259584045129, +5.430127091537531, +5.4117374524717015, +5.393672010993031, +5.3761184336484034, +5.3592621032320915, +5.3432400758592005, +5.3279893402051037, +5.3133453791928646, +5.29914659750826, +5.2853193594848271, +5.2718297809158088, +5.258664194629338, +5.24588054420006, +5.2335725973928966, +5.2218455078786858, +5.2108281448944851, +5.2006635347375569, +5.1914803182356053, +5.18333885231031, +5.1762620823279359, +5.1702627492104689, +5.1653340046103384, +5.1614578760410925, +5.1586254522167305, +5.156873984988712, +5.156265808718997, +5.1568439271086559, +5.1585517615900658, +5.1612788442157136, +5.1649028991800554, +5.169284114098768, +5.1742731148130021, +5.1797247113548481, +5.1855197649290874, +5.1915528288135642, +5.1977395996144633, +5.2040807871825336, +5.2106222048804769, +5.2174145254151192, +5.224501068173784, +5.2319215414284885, +5.2397024600744713, +5.247815094530571, +5.2562018142879889, +5.2647905254194871, +5.2734655822888588, +5.2820882647530176, +5.2905318564305208, +5.2987338958778976, +5.3066655157041165, +5.31429432470168, +5.3215522320178961, +5.3283529269236816, +5.33460823407737, +5.3402313461754769, +5.3451364580585237, +5.3492529846666628, +5.3525747956267633, +5.3551285497081, +5.3569523506416017, +5.35811448845103, +5.358698515331759, +5.3587965202250913, +5.3585285002704968, +5.3580285096049689, +5.3574135126353486, +5.3567192246142374, +5.35594044049295, +5.3550690728951871, +5.3541082320789322, +5.3530666622189189, +5.351958689222144, +5.35081937753839, +5.34969423484465, +5.3486233681058035, +5.3476176865501355, +5.3466733708951519, +5.3457758923884482, +5.3448732464485316, +5.3438944911380828, +5.3427746577410993, +5.3414854112505772, +5.3400169637920119, +5.3383720587070655, +5.336596517563641, +5.3347580141221753, +5.3329266658132326, +5.3311702914806194, +5.329555560690209, +5.3281373837138863, +5.3269208417438394, +5.3258856371860857, +5.3250037544849818, +5.3242288685203247, +5.3235053061641109, +5.3227881767975038, +5.3220843525755646, +5.3214272014136332, +5.3208374523111051, +5.3202659747324095, +5.3196277321145011, +5.3188335703176577, +5.3177977186243872, +5.3164361752892724, +5.3146601237637068, +5.3123588899858349, +5.3094104489684142, +5.3056956631134273, +5.3011127180109279, +5.2955689610868779, +5.2889986335900545, +5.2814472262873275, +5.2730192403780345, +5.2638236971176742, +5.2539522700058061, +5.2434871847009319, +5.2325309377654063, +5.2212761713707643, +5.2099655206902868, +5.1988299338319459, +5.1880214417892283, +5.1776475311122914, +5.1678088857432432, +5.1586054284322724, +5.15013673101285, +5.1424951575328288, +5.1357431404056086, +5.1299259717370509, +5.1250780568495733, +5.1211981076290467, +5.1182642822375772, +5.11625635873369, +5.1151748237881076, +5.11503191659086, +5.1158346557652772, +5.1175594582387864, +5.1201653429817675, +5.1236198624727063, +5.1279411237245851, +5.1331758176428348, +5.139352771664174, +5.1464033382798577, +5.1542040894312517, +5.1626121472810071, +5.1714317477396028, +5.1804379765180641, +5.1894215644197192, +5.19826571191928, +5.2069037427205132, +5.215300968370344, +5.2235332641699284, +5.23173658065217, +5.2400643087004077, +5.24870422624887, +5.2578638242585312, +5.26772171240179, +5.2783215878208249, +5.2896347407300706, +5.3016228609608547, +5.3142530881205214, +5.327494757012694, +5.3413304267804858, +5.355802544516326, +5.3709839423188459, +5.3869563293296823, +5.4038271609970074, +5.4217147953830969, +5.44076036739407, +5.46123894903656, +5.4834871661916136, +5.50779606325154, +5.5342108723025145, +5.5626593135328557, +5.5930205932498671, +5.6251952234944582, +5.6590692375996632, +5.6945077195105593, +5.7312032603915277, +5.7687900550101441, +5.8069068615141468, +5.8452813974113811, +5.8836654367952885, +5.9218316585477924, +5.9597446554026883, +5.9974340611794208, +6.0349374785550758, +6.0721710697470561, +6.1090224780364588, +6.1454172633826758, +6.1814528169174894, +6.2172994577322536, +6.2530950274406534, +6.2888070817561559, +6.3243391101164814, +6.3596148893205644, +6.394651336573479, +6.4295011647425309, +6.4642040442047195, +6.498739328929493, +6.5330636180029753, +6.5671381321296058, +6.6009214735941972, +6.6343807174104583, +6.667461751332028, +6.7000145783990384, +6.7318552544371348, +6.7628152280679226, +6.79273882179244, +6.8214907735699066, +6.8489450081671253, +6.87500151323269, +6.8995711377543083, +6.9225958823516081, +6.9441202541362914, +6.9642287657014368, +6.983001705363213, +7.0004731549164063, +7.0166674573187251, +7.0315818397793013, +7.0450894912421074, +7.05702685979601, +7.0672739444375576, +7.07590172679256, +7.0830439724576841, +7.0888620147075443, +7.0936130864266715, +7.0975860298782463, +7.1010509518551359, +7.1041923161589349, +7.1071670178587176, +7.110069668054444, +7.1127481049246111, +7.114969535551869, +7.1165108753873927, +7.1172091298572671, +7.1169207819335512, +7.1155222447415643, +7.1129659452186109, +7.1092292199372187, +7.1043266218839225, +7.098418932902657, +7.0917153702695366, +7.0843896399803148, +7.0764521696274727, +7.0678594393124472, +7.0586233676712862, +7.049001694805205, +7.0393345799593323, +7.0299385346515182, +7.021014648742689, +7.0127228126043653, +7.00520212561572, +6.9985130327473177, +6.9926906699991305, +6.987723116385391, +6.9834136096663721, +6.9795006772487866, +6.975748628933256, +6.9720501315276575, +6.9683423387094141, +6.964612654901229, +6.9610409274412754, +6.9578752892473243, +6.9553386028631179, +6.9535263206544435, +6.95248886964108, +6.9522439565510838, +6.9526892825528588, +6.9536795309753758, +6.9550552964457344, +6.9566134059002334, +6.9581349616275148, +6.959428252806636, +6.9604190195646094, +6.9610751057974829, +6.9613851726863949, +6.9614096478343157, +6.9612346937991161, +6.9609531042117219, +6.9606763877180491, +6.960522752177372, +6.9606015705493256, +6.960983619896365, +6.9617258910623381, +6.9628651678991877, +6.9643595597380834, +6.96613910045995, +6.9681227386062909, +6.9701930236516025, +6.9722195231760216, +6.9740830111954661, +6.9757145890955234, +6.9770632955322061, +6.9780930385488871, +6.9788230789307368, +6.9792923465084895, +6.9795509480891269, +6.9796885981752883, +6.97980904616121, +6.9800073604857831, +6.9803384155799977, +6.980842836411977, +6.9815516109391762, +6.9824606805511449, +6.983553569098766, +6.9847903926735491, +6.9860390640892938, +6.9871347806811492, +6.9879112331138762, +6.9882065536698468, +6.9878604160102853, +6.98674879755222, +6.98489668504243, +6.9823821051441621, +6.9793055882827293, +6.9758429856905613, +6.9721969449481387, +6.9685673723819423, +6.9651333751172544, +6.9620668400003245, +6.9595063167519289, +6.9574559155980928, +6.9558713984939855, +6.95468571682673, +6.9537540573721408, +6.9529035361959073, +6.9519682400277709, +6.9508203007134739, +6.9493456351660976, +6.94744737333175, +6.9450951041056719, +6.9422826124265988, +6.9390216553883759, +6.9353896086845532, +6.9314878914098381, +6.927425856863783, +6.9233367453214214, +6.9193627073689132, +6.91561761450236, +6.9120955530210537, +6.9087462450457009, +6.9055266248523512, +6.9024394589070726, +6.8995045042446019, +6.8967401154341355, +6.8941527766886868, +6.8917445352008206, +6.88952542149899, +6.8875400384549961, +6.88584595357632, +6.8844873460188225, +6.8834480227329937, +6.8826892553196366, +6.8821955155787666, +6.882055585952374, +6.8823970486867836, +6.8833486059827846, +6.8850294481771641, +6.8875553649710888, +6.8910432615303465, +6.8956163407735405, +6.9013999470225755, +6.9085218366636907, +6.9171295065191511, +6.9273768102571811, +6.9393600613652824, +6.9529204795895581, +6.9678105161085853, +6.9837923505804929, +7.0007166116670376, +7.0184625114257546, +7.0368898080025755, +7.055784403525351, +7.0749016527770863, +7.0940563749523093, +7.1133096337627748, +7.1328073406656207, +7.1526998912360611, +7.1731497950808336, +7.1943201437646263, +7.2163431364531387, +7.2392663627469833, +7.26310077108812, +7.28786619446561, +7.31358896799198, +7.3403081839343161, +7.36800877168611, +7.3965262317176723, +7.4256353536656432, +7.45512303957582, +7.4848212911881511, +7.5145795199872243, +7.5442423963652923, +7.5736020243772444, +7.6024432754243181, +7.6305778502061719, +7.6579338746434464, +7.6844680162776866, +7.7101512050295078, +7.73496112541647, +7.7588926948088819, +7.7819352439418434, +7.804045844880541, +7.82517783876152, +7.8452936010975476, +7.8643747759489537, +7.8824118024537357, +7.8993658079722842, +7.9150811724115568, +7.9293758962626084, +7.9421135094044581, +7.9533174678044363, +7.9630541942871176, +7.9713924760402444, +7.9784127507015175, +7.9841985385239278, +7.9888635321853778, +7.9926294961813866, +7.9957446424585692, +7.9984303960967127, +8.0008128243999437, +8.0029938710799051, +8.0050558653376651, +8.0070111992385637, +8.0088548688086139, +8.0105816072170928, +8.0121851723198052, +8.013658806244333, +8.0149859582227077, +8.0161151098233674, +8.0169863427287371, +8.0175480277389237, +8.0177780966277883, +8.0176618109855742, +8.0171843551062665, +8.0163306375084868, +8.0150854067963433, +8.01342948048763, +8.0113292351685441, +8.0087477472378712, +8.0056577220306959, +8.0020667985255614, +7.9979913874715569, +7.99345288200516, +7.9884909360106438, +7.9831497880264592, +7.9774767588907789, +7.971530159602918, +7.965370902829207, +7.9590448197158006, +7.952540476935904, +7.9458322798177008, +7.938900244390835, +7.93174613851553, +7.9243771317511245, +7.9167953694995283, +7.9089823293746937, +7.9009146767335672, +7.8925941729829976, +7.8841209430508012, +7.8756199531210314, +7.8672096574175665, +7.85898633919424, +7.8510397277694164, +7.8434886407704587, +7.8365644661564513, +7.8305275157146319, +7.825661606831483, +7.82234065431636, +7.8209613166401315, +7.8218662894987592, +7.8251858589345469, +7.8309979416476105, +7.8393611139714432, +7.8502753593966048, +7.86372272454914, +7.8796168259115378, +7.8976245754634533, +7.917349005824164, +7.9384339006829636, +7.9606967259579759, +7.9839944818303046, +8.0081722889523927, +8.0330556531120809, +8.0584594171692387, +8.0842120094885974, +8.1101864684805811, +8.1362677254022735, +8.1623451908850946, +8.1883327061557036, +8.21414952310472, +8.2397236601190489, +8.2649842703597436, +8.2898690281469829, +8.3143243128511326, +8.33833586401051, +8.3618965129927574, +8.3850114551332844, +8.4077221096952517, +8.4300797955048914, +8.4521247133233661, +8.47384509057765, +8.495221758454985, +8.5162350093168442, +8.53685419376032, +8.5570495266476971, +8.5767969184591983, +8.5961006625279559, +8.6149692341721948, +8.6334282375792082, +8.65154683344925, +8.6694067388100464, +8.6870887236339538, +8.7046663717381012, +8.7222123962310114, +8.7397828804673665, +8.75738955390021, +8.7750331231717453, +8.7927217228502954, +8.8104862848049752, +8.8283609552960911, +8.8463671280527869, +8.8644937771608543, +8.8827233808353636, +8.9010623499063541, +8.91957993325342, +8.9383568735270043, +8.9574324159520611, +8.9767458917292124, +8.9962115831996687, +9.0157558288719244, +9.0353295953592472, +9.054889368841506, +9.074359358337432, +9.0935857716531441, +9.1123939186732787, +9.1305852422026312, +9.1478973949233975, +9.1640622314119753, +9.1788697732588922, +9.1922399754610353, +9.20413423526595, +9.21457142563529, +9.2237071881136146, +9.2317309787079864, +9.23886500804143, +9.24540434685685, +9.2516525738521977, +9.25782676922703, +9.26394742215459, +9.2699854531622687, +9.2758772602443038, +9.2814831770478161, +9.2866520504644576, +9.29129319154903, +9.2954506852906125, +9.29920142080046, +9.3026337690410674, +9.3058611747567177, +9.30899739409868, +9.3121064595496765, +9.3151425434263651, +9.3180326053438112, +9.3206918781768149, +9.3230099301263731, +9.3248745914115361, +9.3262104804416257, +9.3270230515936259, +9.3273393271610949, +9.32720721499508, +9.3267205881027682, +9.3259807358372111, +9.3250603754953936, +9.3239694835026974, +9.32270350215451, +9.3212602295283684, +9.3196426177854317, +9.31785782578434, +9.31593788223761, +9.3139695171077612, +9.31205174119744, +9.3102784568048982, +9.308732312992829, +9.3074917913300119, +9.3066226223824984, +9.3061624909079619, +9.3061391873792125, +9.3065531250253564, +9.307344508923201, +9.3084386813488837, +9.3097557190614246, +9.3112041042490929, +9.3126914384885744, +9.31414080611251, +9.3155093038334211, +9.3167652437347677, +9.3179035090081346, +9.318977165399728, +9.3200532698667171, +9.3212010472362863, +9.3224944292263938, +9.3240046532641525, +9.3257714557858691, +9.32776600838519, +9.3299427629154454, +9.3322515396413586, +9.33463219392414, +9.337026229804259, +9.3394081555253088, +9.341823913404502, +9.3443346717187517, +9.34698889118034, +9.3498075660108775, +9.3528003140753437, +9.35593651698829, +9.3590988929908026, +9.36215150308575, +9.3649717614805716, +9.3674658053648958, +9.36955211723826, +9.3711947587316189, +9.3724551744604643, +9.3734191521959076, +9.37418421875383, +9.3748729434613232, +9.3756091202325251, +9.3764790928265356, +9.3774895136066814, +9.378625621229558, +9.3798512694898548, +9.3810848123683, +9.3822362631070391, +9.38323439353287, +9.3840478991469354, +9.3846539460630058, +9.3850219906779877, +9.3851049666849, +9.3848500067217522, +9.3841884248592162, +9.3830172500829683, +9.3812266903691, +9.37871619210656, +9.3754051151105049, +9.3712204740373011, +9.3661131940891309, +9.360086812232808, +9.3531579358686674, +9.3453481584519551, +9.3366885569266582, +9.3272102011020959, +9.316916905598287, +9.3057443689086625, +9.29361340179109, +9.28043729644173, +9.2661096335239979, +9.25052064424344, +9.23356490594491, +9.2151374151442162, +9.195140352048309, +9.1735082407030042, +9.1502314001341816, +9.1253244245810858, +9.0988069985948279, +9.070681820882891, +9.0409610980326942, +9.0096826046590355, +8.9768447840274, +8.9424665321681811, +8.90660983946291, +8.8696378569837453, +8.8319452439860626, +8.7938741310464472, +8.75552005832371, +8.7169219006030509, +8.6782041655707562, +8.63963659754639, +8.60160569730826, +8.5643404762719264, +8.5274976266033455, +8.4905623107740151, +8.4531691665248037, +8.4158831410050752, +8.3794555646153963, +8.3446107618496761, +8.3119870569325762, +8.2821635151376718, +8.255669173008, +8.23271125311425, +8.2134509072258055, +8.1980139009040478, +8.1864926988798, +8.1789243476040738, +8.1752743043085943, +8.1752287515516979, +8.178389912432575, +8.1845378443411931, +8.194215246094787, +8.2082136809817872, +8.2271129631239077, +8.2504962819438479, +8.2776351264776178, +8.3077787808003158, +8.3404442906239478, +8.37518997396847, +8.411567831084847, +8.449057937336, +8.4871203961967474, +8.5252889856621685, +8.563358174680042, +8.601207205421245, +8.6387400632838052, +8.67610503873894, +8.713502620788443, +8.7510693179545616, +8.7886013704990855, +8.8258003976222117, +8.8624424353260434, +8.8984248741589944, +8.9337415976451755, +8.9683377108441729, +9.00192580024131, +9.03415930003219, +9.064762813006606, +9.0938847376495833, +9.121748330129396, +9.1485934691380724, +9.17461099869006, +9.2000147833056811, +9.2250217771375631, +9.2498290807288956, +9.2746410569690632, +9.299587690123392, +9.3245760369419219, +9.34944406334835, +9.3740457620679329, +9.3982783305801032, +9.4220526799867645, +9.4452749313036435, +9.4678211651976127, +9.4895654671583163, +9.51039107596986, +9.530195470246781, +9.5488854162158088, +9.56639164158293, +9.5827232433292391, +9.5979101213760831, +9.6119807304798819, +9.6249553842771629, +9.6368546065409255, +9.6477258511692359, +9.65770163868436, +9.6669353488396119, +9.6755475402643647, +9.6835525473318054, +9.690940597949151, +9.6977346006218337, +9.7040611552131288, +9.7100705661544957, +9.7158813882921926, +9.7215124395281851, +9.726960652145614, +9.7322640831630967, +9.7375878887978331, +9.7431265671187415, +9.7490488903199637, +9.75544788334809, +9.7623966730310769, +9.7699564218983657, +9.7781502197078947, +9.7869903238849965, +9.7964568877961682, +9.8064364161795137, +9.8167920114640985, +9.827383060426568, +9.838060954100257, +9.8486769473524962, +9.8591227926722773, +9.8694075360663316, +9.8795652145658011, +9.8895776407744744, +9.8992733216945759, +9.9084475870904409, +9.9169366229003622, +9.9246900803224278, +9.931680854733612, +9.9377967660416662, +9.9426805922191921, +9.9459212837411126, +9.94718781972895, +9.9463797558491329, +9.9434500814409468, +9.938323937070237, +9.9308478428724136, +9.92085358945898, +9.908241576434186, +9.8930862371503832, +9.87551279893302, +9.855669559137441, +9.83377931975166, +9.8100841029493555, +9.7848029318477, +9.75799855656059, +9.72971004892444, +9.7000276353537522, +9.6692295941417488, +9.6376427716599871, +9.6055634033027051, +9.57316881586608, +9.5405894413043715, +9.507969610093113, +9.4754349528489819, +9.44312817149028, +9.4111446424431868, +9.3793198894418168, +9.3474292767423144, +9.3152426873441563, +9.2825904475314616, +9.24930523331532, +9.2152471360774264, +9.1803321239385589, +9.1445063194004277, +9.1077508346044951, +9.0700945002361131, +9.0316034950648962, +8.9923467782703312, +8.95245355230579, +8.912067053151338, +8.8713323482932545, +8.8303438620645469, +8.7891811784702423, +8.74792286469846, +8.7065318897563735, +8.6649371007473448, +8.6231050770557118, +8.5811463714208411, +8.5392505504821123, +8.497609275942315, +8.4566912223048725, +8.4170558767846835, +8.37925992866909, +8.3439171076903467, +8.3116718180161442, +8.283139987711138, +8.2586848457294426, +8.2385491740876731, +8.2229255361305231, +8.2119090042880512, +8.2054897076355182, +8.2036314973598277, +8.2063049498270821, +8.2134801726104918, +8.22513429808772, +8.2413230945753764, +8.2621637222419064, +8.2876816579282071, +8.3175662444720082, +8.3512796788962724, +8.3882331987044356, +8.4280426156857633, +8.470447850194919, +8.51522234525685, +8.5617495067188845, +8.6092225629108921, +8.656844701243573, +8.7042914988697948, +8.7514590566322585, +8.7982313456493841, +8.8446510133849578, +8.8907992228291768, +8.9368091785346415, +8.9827450894457179, +9.0286897589484028, +9.07475949036609, +9.1211165253094, +9.16797919334464, +9.21548598148518, +9.2635018675257346, +9.3117112797288559, +9.3598142168014977, +9.40754505450129, +9.4546852511666035, +9.50100486117864, +9.5462023825515558, +9.5899426303566511, +9.6319313070507224, +9.67186200356986, +9.7094614330473838, +9.7444849420090165, +9.7767399407760767, +9.8060683286793591, +9.83236071388965, +9.8556487208973138, +9.876054951105635, +9.893713256460714, +9.9087242704925451, +9.921178235981305, +9.9311497926013228, +9.9386459762713137, +9.94363522438342, +9.946147876643483, +9.946512360237282, +9.9452256063005589, +9.9427659398966988, +9.9394203375814225, +9.9353681147530981, +9.930817072009642, +9.9261673194781554, +9.9219270117316931, +9.9185163770927645, +9.9159030841033857, +9.9138001617069911, +9.9119150599067876, +9.9100954299144419, +9.9082680393374254, +9.9063620054035688, +9.9042649930050963, +9.9018411981946421, +9.8989590011179374, +9.895519966354211, +9.8914447378376753, +9.8866658599304209, +9.881154125696753, +9.8749025898154041, +9.8679080378565978, +9.8601682806112123, +9.8516818575928475, +9.842433455007745, +9.8323396944710737, +9.8212768786889875, +9.8091561924307253, +9.7960734529609255, +9.7822371975352169, +9.7678442185175083, +9.7529496059099934, +9.7375203689297631, +9.7215674822414258, +9.7053649975855425, +9.689354909958892, +9.6739618829583254, +9.65942085587666, +9.6458402011847877, +9.63331363907911, +9.6219604120844391, +9.6119185285753552, +9.6032845453399975, +9.595956644019445, +9.5896997972592342, +9.58429156712466, +9.57966897508106, +9.5758750247715341, +9.5730100340063551, +9.5713533033226668, +9.57130452761276, +9.5732279089228278, +9.5772340677435182, +9.5832644712697466, +9.5912200695746943, +9.600951758369817, +9.6122766110717812, +9.6249930258003555, +9.63884520688526, +9.6535409896528925, +9.6688385697573871, +9.6847610587497144, +9.7015031510976684, +9.7192608469557236, +9.7381202918343579, +9.7580956011714122, +9.7791803061019813, +9.80137078859002, +9.82466106786168, +9.8490215552709479, +9.8742823786447556, +9.90019310700632, +9.9265012723379371, +9.9530073926089173, +9.9795432502497974, +10.00593506529686, +10.031999827602831, +10.057539935337667, +10.082389543819835, +10.106510773352777, +10.129948872724128, +10.152748555724758, +10.174857110616562, +10.196173218432047, +10.216603737912569, +10.236101674502322, +10.254648337813876, +10.272257813665743, +10.289103016607291, +10.305435757236067, +10.321514204267967, +10.337569402763616, +10.353821033121157, +10.370450398692839, +10.387440023897945, +10.404675020599315, +10.422005472639295, +10.439209024391497, +10.456020165837126, +10.472205389824607, +10.487715614446174, +10.502589847602927, +10.516898666478628, +10.530779550839435, +10.544409210876463, +10.557949659485395, +10.571468161421393, +10.584987704072173, +10.598501810683677, +10.611910778732192, +10.625067511006987, +10.637831524839227, +10.650113779233992, +10.661850283961874, +10.672990749443711, +10.683525559595413, +10.693465352868692, +10.702831147834393, +10.711677914265252, +10.720076050660415, +10.728090282770964, +10.735751658465915, +10.743076227578793, +10.750073319501164, +10.756729362283625, +10.763021038335514, +10.768908349921482, +10.774286061320188, +10.779019188255068, +10.782983130261679, +10.786112946593885, +10.788370291080463, +10.789713046069997, +10.790069411203817, +10.789354575335969, +10.787500387465982, +10.784516653996542, +10.780449139151074, +10.775596519607019, +10.770259945233608, +10.764455834747732, +10.74657587044018, +10.733883429412375, +10.726427895677809, +10.720258002709299, +10.716680469259193], +"RacingK":[-0.013651831668281126, +-0.013651831668281126, +-0.013460195195560383, +-0.013460195195560383, +-0.013460195195560383, +-0.013460195195560383, +-0.013460195195560383, +-0.013460195195560383, +-0.013460195195560383, +-0.012936285773105537, +-0.011669715293771282, +-0.009723633060976445, +-0.0071657412512930729, +-0.0040631676518984531, +-0.00099387913506039931, +0.0017850195993833126, +0.0043124586065933449, +0.0066394236777282, +0.0088222998009194562, +0.010909330776599554, +0.012934974552911415, +0.014920584335822978, +0.016879080014852374, +0.018808145316759256, +0.020689573111477629, +0.022492972080937479, +0.024179636714029427, +0.025705204694569272, +0.027025953530693127, +0.028092109066297603, +0.028845164985794536, +0.029217064344646892, +0.029137332626890725, +0.028537217007219947, +0.027361147123282061, +0.025580093015535491, +0.023192657604571541, +0.02022335201236538, +0.016743879479390988, +0.012876106224398432, +0.0087783172564865047, +0.0046336063445513841, +0.00064134579164238856, +-0.0030151106563306431, +-0.0062075065306129891, +-0.0088685523629949865, +-0.010977798002293352, +-0.012537919680191266, +-0.013560725048357527, +-0.014035090568502755, +-0.013921741469976831, +-0.013159997448199845, +-0.011685213039934533, +-0.0094190424859749936, +-0.0062657011846811595, +-0.0021274052699627533, +0.0030369012180472051, +0.00919620851060089, +0.016231502594626836, +0.0239155625514109, +0.031936351222893032, +0.039956920281565257, +0.047650479626328485, +0.054699369109108484, +0.060822453728801941, +0.065791238993549384, +0.069435506383174875, +0.0716307167542924, +0.072346462548408472, +0.071647123461073, +0.069670193678082512, +0.066603816150902675, +0.062678771350189039, +0.05812479508561727, +0.053169783822505173, +0.048044834993921537, +0.042987887111268185, +0.038208372201634741, +0.033872863256874365, +0.030091924731808391, +0.02690450393678194, +0.024288053360828916, +0.022189996170470856, +0.020537484984618038, +0.019240348942495315, +0.018204593337761792, +0.017342225191883054, +0.016573972440617629, +0.015833978121648759, +0.015078538196387674, +0.014285823550392053, +0.013447763862012022, +0.012564716011912346, +0.011641875448429198, +0.010680302170155948, +0.0096730637081083523, +0.0086059651078880216, +0.0074619278760692078, +0.0063001132611300711, +0.0050018432165843067, +0.0035411601154865524, +0.0019545948943501088, +0.00024364734446100881, +-0.0015777318390619989, +-0.0034919787560171705, +-0.0054730045351199059, +-0.007468203344388284, +-0.0094191787679981133, +-0.011281575255304935, +-0.013056264475231885, +-0.01475494596438566, +-0.016382842979429459, +-0.017924455503253819, +-0.019359609070510903, +-0.020670444436384633, +-0.021845620301630442, +-0.022875260167908577, +-0.023734059701474325, +-0.024346304445599438, +-0.024623849871382851, +-0.024490593545477959, +-0.023908817016209186, +-0.022851270812687841, +-0.021298991525602384, +-0.019261690530261291, +-0.016756114564860879, +-0.013782023806882362, +-0.010280483438745248, +-0.0061790115774345757, +-0.0014361091190971493, +0.0038754802862237224, +0.0096615806724590809, +0.015825508822230119, +0.022290573823350375, +0.02897926866539266, +0.035772813078291485, +0.042416120603050146, +0.048627080960187738, +0.054173696114882326, +0.059025794602813222, +0.063202705486409425, +0.066730963903280566, +0.069660068607681411, +0.072052744383247991, +0.073984123425504131, +0.075522035808170448, +0.0767454545018272, +0.077731416795232475, +0.07859148484841072, +0.079429215692022187, +0.080328452447247109, +0.081406868163756613, +0.082762512447646278, +0.084457482038169454, +0.086298360172183383, +0.088090101568222223, +0.08960263560682824, +0.090420419305407479, +0.090129895172359364, +0.088400521411358041, +0.085149738980645817, +0.080344046433132352, +0.074076241684287156, +0.066944589187472814, +0.059562671417318809, +0.052547781033876237, +0.046471770425138517, +0.041888077848216791, +0.0391602498652686, +0.038121434116002106, +0.038523566876119957, +0.040045587481942826, +0.042228296061053723, +0.044577213811532367, +0.046666606199465867, +0.048246145828884132, +0.049113183464451565, +0.049153944541411115, +0.048447570871205263, +0.047131315171830966, +0.045347726179234292, +0.0432461766068615, +0.040979853593462755, +0.038674693274781756, +0.036403138656227865, +0.034219876091847651, +0.032189249984091804, +0.030400098280331141, +0.028941309347019131, +0.027860232106370977, +0.027106245597209012, +0.026605711399342355, +0.026277617457580189, +0.026024077387329446, +0.025746351326103156, +0.025372154318191186, +0.024890552474996924, +0.024305853094700312, +0.02364040648961677, +0.022956606149990059, +0.022324205444555319, +0.021797621337071135, +0.021395999986309831, +0.021127608384990958, +0.02097009688469411, +0.020835412831275331, +0.020621794002877405, +0.02024155088591004, +0.019637551508759371, +0.01876287669251854, +0.017599041205250313, +0.016187870110032667, +0.014586669787391329, +0.012862117629522867, +0.011100287805593523, +0.0093907954615241561, +0.0078117564140176149, +0.0064178653942831322, +0.0052550787110160107, +0.0043455607225586831, +0.0036620112614333036, +0.0031650885850477953, +0.0028123909716376611, +0.0025551627908907675, +0.0023435829730049903, +0.0021309116825542823, +0.0018767631435835359, +0.0015447336140679195, +0.0011178681484510066, +0.00061942495184083937, +8.1531205048364453E-5, +-0.00046796741389950241, +-0.0010100793034222826, +-0.0015267821738189895, +-0.0019916106705714369, +-0.002360684176403264, +-0.0025872562510825658, +-0.0026341719356123864, +-0.0024840407524006347, +-0.00212444045532914, +-0.0015457125037483253, +-0.00074390052375004163, +0.00028134912785656867, +0.0015127562365705787, +0.0028970822780143555, +0.0043721285024776856, +0.005872226077952453, +0.0073247278103539346, +0.0086578532481487412, +0.00981903169218053, +0.010794694423579231, +0.011581058342996489, +0.012178986660930646, +0.012598712849693074, +0.012853628140983737, +0.012964052350636484, +0.012964033432540104, +0.012888816784569176, +0.012758022646774, +0.012560172788336866, +0.012277300795382994, +0.0118969608033346, +0.011417545548175322, +0.010839272752417327, +0.010156879718881455, +0.0093543242603892334, +0.0084146486601131849, +0.0073323072895541755, +0.0061242384436724735, +0.0048116491362966375, +0.0034089902681937586, +0.0019174858545385597, +0.00033654980733757077, +-0.001324068856316426, +-0.0030341912643258324, +-0.004760601222880678, +-0.006483823980883009, +-0.0082119374663020377, +-0.0099593082343242389, +-0.01174121999638085, +-0.013576438399311061, +-0.015483232116857128, +-0.017471688171399279, +-0.019534114505026377, +-0.021658377743689741, +-0.023815634617816675, +-0.025941577118283651, +-0.027963787923271852, +-0.029810215250116796, +-0.031410561217125904, +-0.032697406795333124, +-0.0336382939555755, +-0.034282084378761506, +-0.034696423684781964, +-0.034955047204264761, +-0.03514514649212655, +-0.035356412809704613, +-0.035662508163674868, +-0.036093697959623333, +-0.036669661124811181, +-0.037387967419318956, +-0.038190673668083236, +-0.039006550748122891, +-0.039773930369178728, +-0.040460910961528693, +-0.041042180810808078, +-0.041504647382385948, +-0.041869577282007464, +-0.042167050346111269, +-0.042428855888439226, +-0.042691780271579986, +-0.042993676147374531, +-0.043362807666200619, +-0.043797757813769933, +-0.044289801559033025, +-0.044824568040489024, +-0.045357261056216763, +-0.045839013702009837, +-0.04622549178454817, +-0.046485963576581538, +-0.046593442398123776, +-0.046531660938695395, +-0.046348490475318312, +-0.046101127071512274, +-0.045854372855800796, +-0.045712567458310462, +-0.045787117546992842, +-0.046174345742111662, +-0.046874009246926265, +-0.047868930734606012, +-0.049122181659296035, +-0.050517943593718112, +-0.051916326503409577, +-0.0531805931276734, +-0.054216241718048085, +-0.054934209347235745, +-0.055264692462005528, +-0.05523853271123616, +-0.054915505837090615, +-0.054367098511204491, +-0.053664200041801488, +-0.052889419421255947, +-0.052111696689243751, +-0.051302662825852323, +-0.050407939571459913, +-0.049373867838310964, +-0.04818990346845603, +-0.046854803705061204, +-0.045375641755875565, +-0.043811765232186932, +-0.042235972115863094, +-0.040725331577691724, +-0.039363501302027822, +-0.038239368479677203, +-0.037423341728168788, +-0.036886034662526726, +-0.036559943367237342, +-0.036365569949501457, +-0.036203586118097431, +-0.035962357302359742, +-0.035544722905847669, +-0.03493411877767872, +-0.034149191413755407, +-0.033217335955578728, +-0.032181796832559534, +-0.031094792310537391, +-0.030007002076689038, +-0.02894699847097966, +-0.027935290579901031, +-0.026979303478420327, +-0.026037128595135357, +-0.025040761284289042, +-0.023925756091575042, +-0.022662253307868814, +-0.021237525593219821, +-0.019645600236286247, +-0.017900524616671038, +-0.016027134166423353, +-0.01405079199520233, +-0.011991715870264638, +-0.0098679093922923247, +-0.0076984888944302155, +-0.0055095523618997515, +-0.003330709800142646, +-0.0011919549899023943, +0.00087723341771645728, +0.002847639522910794, +0.0046889737826148834, +0.00636643411517493, +0.0078426640125403655, +0.0090892957034105215, +0.010118967929942428, +0.010966459149905709, +0.011670253193307757, +0.012271100145228109, +0.012811103192543406, +0.013328484887827449, +0.013843407235171312, +0.014366518570962552, +0.014900524328161788, +0.015419472115853705, +0.015882279145738115, +0.016249460740416912, +0.016497430780514206, +0.016610947778603433, +0.016576951787677756, +0.016386794469678858, +0.016034120903695128, +0.015515371231839777, +0.014837001945133706, +0.01401079094632127, +0.013049192810435475, +0.011964597792487045, +0.010769358905769442, +0.0094791790479176359, +0.008124394022855936, +0.0067427796762376847, +0.0053744049919713611, +0.0040652186316551377, +0.0028640927666605475, +0.0018127169501732316, +0.00092036261288055889, +0.00017993643845258964, +-0.00041884516852685842, +-0.00089049135148759335, +-0.0012516373175168818, +-0.0015195663964468694, +-0.0017131489385544074, +-0.00185204867950651, +-0.0019533318802787344, +-0.0020225138959913624, +-0.0020592915030321676, +-0.00206509927496136, +-0.0020521895887474066, +-0.0020382683054553583, +-0.0020409487721791877, +-0.0020743008921122554, +-0.0021506045611515028, +-0.0022781590834869562, +-0.002449206446568332, +-0.002647863086367466, +-0.0028553268595336518, +-0.003044989255353956, +-0.00318627721058813, +-0.0032525546900721062, +-0.0032363990126882836, +-0.0031401482654605144, +-0.002970637473320516, +-0.002748335681159157, +-0.0025006483634436019, +-0.0022531231762703335, +-0.0020192743235560523, +-0.0018064870788907041, +-0.0016223607587621002, +-0.0014790000520572063, +-0.0013908048541379733, +-0.0013713597875274494, +-0.0014294404450595623, +-0.0015713480953829159, +-0.001806837264206591, +-0.0021619838719483388, +-0.0026712731255604358, +-0.0033657538956381344, +-0.0042571838530070993, +-0.0053472722253104094, +-0.0066307925360019337, +-0.0080783091246909265, +-0.0096479731963955186, +-0.011295909135813588, +-0.01297732144378088, +-0.014646957011069018, +-0.016255648400524625, +-0.017737850599770882, +-0.019019103469939833, +-0.020033537858803505, +-0.020757373454666314, +-0.021189993930059322, +-0.021333275020071679, +-0.021185396723456883, +-0.020742472651638838, +-0.020006700862437419, +-0.019006833024106554, +-0.017786640007040062, +-0.016389801535762298, +-0.014850446361277688, +-0.013197335125320248, +-0.011457330775978866, +-0.009652455691026237, +-0.0078021696271040894, +-0.0059254987717365379, +-0.0040415791666296589, +-0.0021695970317065624, +-0.00032442989651024646, +0.001498224360679158, +0.0033136060353167076, +0.0051326497732494415, +0.0069399010290400968, +0.00870531045376697, +0.010395606994476697, +0.011972622864007069, +0.01339548506596273, +0.014624842422311858, +0.015630515258953856, +0.016387108303329193, +0.016880396387550851, +0.017142435019565697, +0.017230971257191547, +0.017211951595753641, +0.017170795142892797, +0.017203757089920356, +0.017397210433694923, +0.017787046957882226, +0.018381807281720466, +0.019180669492155786, +0.020159100051803439, +0.021279955616440121, +0.022505147967102006, +0.023801974958123282, +0.025140362927766856, +0.026498794380015886, +0.027891764491630784, +0.029352178192476562, +0.030919927629606943, +0.03266311364958057, +0.034663676134717179, +0.036990783475714377, +0.039644952802957004, +0.042594271196410349, +0.045793386910453912, +0.049196124146039147, +0.052751462757945546, +0.056398708985767036, +0.060004823884297329, +0.063415366186213712, +0.06648565385957865, +0.06914634841244223, +0.071356570977835848, +0.073092001322749525, +0.074365203717828329, +0.075209171008337281, +0.075662862595821265, +0.075777910332174653, +0.075611199921294447, +0.0752265046383311, +0.074704826260393209, +0.074139415731349259, +0.0736118405203646, +0.073122354626375966, +0.0726427928270387, +0.072147646208476829, +0.0716596203787564, +0.071215437614117277, +0.070840360906318636, +0.07050756212937935, +0.0701693699766552, +0.0697866446666949, +0.069357945765628828, +0.0688974784077993, +0.06841006600442022, +0.067858369459081386, +0.067189805080912213, +0.066358108164682933, +0.065333404836709019, +0.064095298871498, +0.062624384412836367, +0.060907067278154009, +0.05893128016972083, +0.056696200269997284, +0.05424495071858746, +0.051637412560938727, +0.048928961656006111, +0.046161237594971052, +0.043370173161164455, +0.040583352913166393, +0.037794396701419333, +0.034987302349834312, +0.032148277851499527, +0.029282269049217619, +0.026400704620313728, +0.023521634772149795, +0.0206946837795691, +0.017978582482121655, +0.015434059641413624, +0.013130404635121841, +0.011138952790519028, +0.0095074263269307874, +0.0081859601063503911, +0.0070930930708359673, +0.0061432494661267829, +0.0052429029070664972, +0.0042959874400021183, +0.0032151160884291837, +0.0019489387147427568, +0.00045762488988939178, +-0.0012765476075445473, +-0.0031840222909196763, +-0.005166691130572016, +-0.0071364727591512042, +-0.0090550061927368065, +-0.010900174373782332, +-0.012641874635080144, +-0.014211794280011895, +-0.015529443839085772, +-0.016527798935677442, +-0.017197952371818665, +-0.017550802026193475, +-0.017594100050461831, +-0.01731696872838652, +-0.016701985011773737, +-0.015754392799827214, +-0.014575081110719786, +-0.013297451891029594, +-0.012044061549246489, +-0.010883362904204155, +-0.0098648603025070329, +-0.00902225642022655, +-0.0083290021097396083, +-0.0077379301420469988, +-0.0071970040952588034, +-0.0066415476923330575, +-0.006002304943079623, +-0.00522292825883717, +-0.0043022530816879409, +-0.003258507894092023, +-0.0021242361937299828, +-0.00098440766101003368, +5.7187686177666641E-5, +0.0009083827187782767, +0.0015314035939924971, +0.0019078665533915663, +0.0020313029089547656, +0.0019378530235441293, +0.0016789490794473197, +0.0013106327447907342, +0.00090284003263156826, +0.00053050437957526759, +0.000260563152899724, +0.00012526204112569777, +0.00014441704577614398, +0.00032872147126272689, +0.000655425934532499, +0.0010898234819153377, +0.0015932757994559191, +0.0021148960414178841, +0.0025994250892013159, +0.0029960573307503163, +0.0032737498848367051, +0.0034085122618210686, +0.003384148559783771, +0.0032142516360429522, +0.00292302314333865, +0.0025396141980371123, +0.0021100726681596398, +0.001686454212932457, +0.0013163929460033308, +0.0010273937412015558, +0.00083980359380323756, +0.0007685191029334472, +0.00080834017628434785, +0.00094694640154665936, +0.0011643347450669827, +0.0014112104250699193, +0.0016278964591195, +0.0017563162167016089, +0.0017483085256074613, +0.0015592272542962597, +0.0011546388743691647, +0.0005410493924983815, +-0.00026052890050936363, +-0.0012188907933287985, +-0.0022656649249630564, +-0.0033192077938624656, +-0.0042981617046949552, +-0.0051267622688178065, +-0.0057311816201624875, +-0.0060530930318110267, +-0.0060971668736623293, +-0.0058906085253922127, +-0.0054706589654726495, +-0.0049085414982813916, +-0.0042876659589778949, +-0.0036892745387890531, +-0.0031815248411754893, +-0.0028279285416352349, +-0.0026807740730735307, +-0.0027477591680193751, +-0.0030204397863130015, +-0.0034813167614917775, +-0.0040810762184032342, +-0.004758817442857899, +-0.0054534086719013122, +-0.0061068143355283277, +-0.0066621049008974273, +-0.0070724667893952275, +-0.0073324632821754132, +-0.0074518900593748948, +-0.0074429068348509583, +-0.007322023655770624, +-0.0071073637242630395, +-0.0068191378516444419, +-0.0064854919533891414, +-0.006137551429574205, +-0.00579840622975424, +-0.005456890283503114, +-0.0050890601898985633, +-0.0046755233915214836, +-0.0042204619379084332, +-0.0037368540915593343, +-0.0032322319953497062, +-0.0026883563208357931, +-0.0020773468164307224, +-0.0013728239454941877, +-0.00055820316896660173, +0.0003794464059022901, +0.0014562948645454449, +0.0027034280019303178, +0.0041573596294432981, +0.0058499305102861533, +0.0077939871279681045, +0.0099954866678988522, +0.012447438168154423, +0.015087741060062916, +0.017836089585988094, +0.020613467648210537, +0.023359552178409161, +0.026019332972510769, +0.028533315877925621, +0.03082048040352757, +0.032792286226985073, +0.034385892693606306, +0.035650052460888683, +0.036672638654898108, +0.037540083650518086, +0.03832159381791464, +0.039080323607022155, +0.039877216320388854, +0.0407711635224933, +0.041819557544338817, +0.043067931394025157, +0.04450704950457695, +0.046113194426763905, +0.047849751013425187, +0.049644762565384574, +0.051411173860257411, +0.053071809204692358, +0.054577933124042272, +0.055894578227049116, +0.056982807404877593, +0.057790654196729248, +0.058261332655876852, +0.0583564257483824, +0.058096688555616019, +0.05752276065893424, +0.0566756246814156, +0.055588053590762194, +0.054292155846068259, +0.052820181297801076, +0.051208547095155342, +0.0494950852931242, +0.047713386360398527, +0.045874777309877421, +0.043986959226406171, +0.04204788476400205, +0.040027117587037996, +0.037885825908541525, +0.035596031706433814, +0.033172221031976513, +0.030639770613408342, +0.028022311524378146, +0.025341400604823532, +0.022618257893850663, +0.019886828139363679, +0.017231013666888711, +0.014746432557869778, +0.012512582876769259, +0.010552151883069216, +0.0088732214222487175, +0.0074787951825397844, +0.0063536890427296107, +0.00547816266925703, +0.0048256266258395152, +0.0043453736533091538, +0.0039807462176738081, +0.0036789202757866223, +0.0034004437234517468, +0.0031093606476232309, +0.002775933009953982, +0.0023925099823304818, +0.0019569339604986239, +0.001467086779348917, +0.00092100577277200548, +0.0003168038346622879, +-0.00034611969516187878, +-0.0010638000595426707, +-0.0018311265688392994, +-0.00264266054265821, +-0.0034917719647609463, +-0.0043715473525545619, +-0.0052739228635269812, +-0.0061867288713342182, +-0.0070967634747354244, +-0.0079892673577029779, +-0.0088438290570759161, +-0.0096387482910676534, +-0.010357825244843636, +-0.011005293319896543, +-0.011590481253702378, +-0.012122521319844358, +-0.012609799746082083, +-0.013060548840033459, +-0.013484795454356805, +-0.013899585030733954, +-0.014323615374184565, +-0.014766678678490609, +-0.015204029060790917, +-0.015602275119147078, +-0.015930684256642205, +-0.016168273925072696, +-0.016296709782469526, +-0.016290080966980178, +-0.016092835315037607, +-0.015641925803975051, +-0.01487463521181254, +-0.013730161727175354, +-0.012148019384962171, +-0.010078230491257298, +-0.0075133437256967315, +-0.0044560257862061216, +-0.00091978532905012743, +0.0030442348120271905, +0.0073742617375851327, +0.011988654030989372, +0.016728880132106955, +0.021419734391443387, +0.025905512677308666, +0.030115800268387536, +0.034002272727359666, +0.037517370282917767, +0.0406217196986404, +0.043278631591705807, +0.045469323250654212, +0.047239480316762616, +0.048652169622646978, +0.0497616346534877, +0.050589231883549461, +0.051148801811749869, +0.0514588259802861, +0.051542412673110924, +0.051426905500962947, +0.051138378133311659, +0.050701775130910245, +0.050141189157436837, +0.049482299643833563, +0.048753563955866594, +0.047984346858316033, +0.0471997472497612, +0.046412873931611913, +0.045633367466108368, +0.044868715174206687, +0.044115125125690241, +0.043367644632567447, +0.042619546098033194, +0.041862446270749247, +0.041086869504719223, +0.040289609146248628, +0.039488771184233211, +0.038706738272247736, +0.0379659396830436, +0.037289533694899624, +0.036700442636884364, +0.036216577644956616, +0.03583960586997436, +0.035567778600367833, +0.035396985391348959, +0.035318649254871666, +0.035322188717175081, +0.035394486516023727, +0.035516702092006996, +0.035668722540501116, +0.035839450898523514, +0.036041702917614604, +0.036293393376107867, +0.036601663710876024, +0.0369461364171922, +0.037300073613942206, +0.0376423193273937, +0.037964391333674408, +0.038260532683101978, +0.038512414364949947, +0.038670354718373823, +0.03867755287239337, +0.038481480601200421, +0.038037321255086978, +0.037304365819559079, +0.0362520316373537, +0.034873199366942664, +0.033169114479171993, +0.031160713275065217, +0.028916571880480885, +0.026518242944936612, +0.024059481624871374, +0.021664480425599056, +0.019460163399498624, +0.017541495154736651, +0.015930692363711269, +0.014630037727518013, +0.013620982281299248, +0.012837681507372819, +0.012204323908956403, +0.011651007077677702, +0.011121921916737571, +0.01056674536997259, +0.0099571663209626834, +0.009313948988688316, +0.008668857439879005, +0.0080503711478936268, +0.0074793253622007852, +0.0069730756949613667, +0.0065328422939892666, +0.0061242382396938452, +0.0057052313871218691, +0.0052393900216473012, +0.00470273710682614, +0.0040760163885329524, +0.0033556983615679074, +0.0025728418361865039, +0.0017661795511237726, +0.00097070707402157036, +0.00021316779558730426, +-0.00048251943601886293, +-0.0011000996389828829, +-0.0016401283667928442, +-0.0021070219532380763, +-0.0025043102683271223, +-0.0028335778859932318, +-0.0030953301496730863, +-0.0032848582894441803, +-0.0033860150003995875, +-0.003380349286087369, +-0.0032527691251094809, +-0.0029955603217691035, +-0.0026041361217234238, +-0.0020855161963221768, +-0.001472255699624971, +-0.00080293847606347033, +-0.00011618952931455834, +0.00054929068640468994, +0.0011555206146967006, +0.0016707920596207885, +0.0020771906339984371, +0.0023614866454479506, +0.0025224398958968029, +0.0025851284091849081, +0.0025810479841098383, +0.0025433508001715273, +0.0025088161321982303, +0.0025138273552791535, +0.0025843370443095247, +0.0027234847503595154, +0.0029281868662031927, +0.0031884037175402393, +0.0034789597499593141, +0.0037719300744453572, +0.0040462271447919019, +0.0042956209280418959, +0.0045178893237333246, +0.0047150160833537838, +0.0048980850858643711, +0.0050793704531036515, +0.00526325577557951, +0.0054370520155656819, +0.0055835322073601859, +0.0056810672981086312, +0.0056985615307493624, +0.0056042831118721693, +0.0053794509148790762, +0.0050330660249859622, +0.0045820730669270671, +0.0040549983578093973, +0.0035051699581354397, +0.0029903210963928128, +0.0025568964307639578, +0.0022272306748357994, +0.0020161503488597197, +0.0019235669225961709, +0.0019176536629500404, +0.0019593311283456552, +0.0020110952739804517, +0.0020387665834812139, +0.0020097844138726464, +0.0018981833805991112, +0.0016920289266076055, +0.0013828525937186972, +0.00096337554792554449, +0.00042882890732638332, +-0.00022519633635150111, +-0.0010051675666901728, +-0.0019219894135547829, +-0.002986801351080948, +-0.0042036338258392113, +-0.0055612187523134066, +-0.0070441038463418572, +-0.0086322787781905313, +-0.010296004453280976, +-0.012004061979865317, +-0.013733489396665188, +-0.01548065280628615, +-0.017247095839184236, +-0.0190410833291914, +-0.020886740281507495, +-0.02281231596127033, +-0.024845888785836857, +-0.027017434164622246, +-0.029355512421197754, +-0.031875506903498642, +-0.034564799949432769, +-0.037403065271384012, +-0.040366935180937771, +-0.043431320985623731, +-0.046570263422503935, +-0.049752552278297793, +-0.052954235556767308, +-0.056150270990025383, +-0.059308897430918613, +-0.06234520160388933, +-0.065178422261325808, +-0.06773977545594044, +-0.070010839219968576, +-0.071983154863317425, +-0.073636739018883554, +-0.074910252864403337, +-0.075724755153269, +-0.076042447184703224, +-0.076019438968567568, +-0.075856625557840215, +-0.075712456817125975, +-0.075478070463269126, +-0.074995850388087509, +-0.074134135960441827, +-0.072810247865703, +-0.070980199725951112, +-0.068579163058490322, +-0.0654890917731329, +-0.061563186021960127, +-0.056692258820149929, +-0.05098215225403506, +-0.044585299548275975, +-0.037666139518712838, +-0.030422587830186906, +-0.023081705971259796, +-0.015816630819628561, +-0.00855925293477976, +-0.0011675877923312933, +0.006462572621848039, +0.014216379989939732, +0.021928727358371168, +0.029438401289502446, +0.03671085323670923, +0.043735023912875065, +0.05046208712125911, +0.056644400044029514, +0.0619934033229599, +0.066276192589770716, +0.0695404462477913, +0.071920385694652075, +0.073561739066502152, +0.074603536702568529, +0.075189044900159652, +0.075448973969244257, +0.075455097596952125, +0.075261903011349163, +0.0749230769114507, +0.07446040232768647, +0.07389887266970574, +0.073247761566869074, +0.0724091880255265, +0.071261573956320018, +0.069712850287327613, +0.06784182755046328, +0.065764555704127092, +0.063584623384818434, +0.061368651054400536, +0.059163860375848726, +0.057031593232620734, +0.0550789662335182, +0.05343061152646026, +0.052175702338987009, +0.051258897121363445, +0.050595348239083918, +0.050098890834043695, +0.0497040628975475, +0.049343255951972635, +0.048947449863072104, +0.048445226145003163, +0.047763367744540049, +0.046847486821890619, +0.045695384667564475, +0.044322462693463675, +0.042745617757441734, +0.040989359894763176, +0.039080490361036828, +0.037046303312793766, +0.034918754490755391, +0.032730579771166987, +0.03051815958211735, +0.02833356060796078, +0.026231819184185164, +0.024255192817613222, +0.022404698555648243, +0.020671669067775983, +0.0190546983038366, +0.017577349875019108, +0.01626853899224346, +0.015144063081669787, +0.014178609774427735, +0.013337380007738531, +0.01260201674998246, +0.012006076072684512, +0.011595013010339121, +0.011401223905062772, +0.011417223858016395, +0.011625895421504653, +0.012014675674426224, +0.012584501924349581, +0.013338777115807126, +0.014264512125291775, +0.015299738919110887, +0.016370716351697491, +0.017408727482934271, +0.018359990726794763, +0.019175142484247877, +0.019816462403711738, +0.020280826358028841, +0.020573211435481652, +0.020694187646240935, +0.020630875986392135, +0.020368169794145616, +0.019900889736999619, +0.01925083302686996, +0.018445048385439786, +0.017482522821747667, +0.016281617757950766, +0.014743505200540307, +0.012798664213270411, +0.010463049380805717, +0.0077716250372457749, +0.0047445359597900333, +0.0013596462498046103, +-0.0024145063144135853, +-0.0065755730861889574, +-0.011028632501880705, +-0.015654232247015017, +-0.020344727058114836, +-0.025025440636986182, +-0.029635026393203191, +-0.034109901879364093, +-0.038402518847793214, +-0.042467605703602862, +-0.046260774106631028, +-0.049734285087212012, +-0.05284446459477881, +-0.055560184045526595, +-0.057891361416257954, +-0.059863514517140511, +-0.061491446289143124, +-0.0627642620108133, +-0.063658419470122, +-0.064172757770655786, +-0.064406378476932521, +-0.064481942582435975, +-0.064513711757946776, +-0.064578326426165483, +-0.064741693618115673, +-0.065065702222929234, +-0.0655962437986087, +-0.066376027568282481, +-0.067430427599917381, +-0.068719443986228659, +-0.0701795272282709, +-0.071745076255989845, +-0.073348220939123632, +-0.07492138502081315, +-0.076401747222220276, +-0.077750265754032821, +-0.07893693105355179, +-0.0799397472971142, +-0.080773357600249271, +-0.081467576246679482, +-0.082044605351484778, +-0.082506418164649237, +-0.082842883846359766, +-0.083043971369187813, +-0.083025941137174736, +-0.082683589085948528, +-0.081911726729496662, +-0.080566168024831686, +-0.078488376723128223, +-0.075535018640962584, +-0.071648241596130646, +-0.0668160743605386, +-0.06103853076984686, +-0.054402306623983071, +-0.047031414652010994, +-0.039054413162796328, +-0.030602862816394263, +-0.021831845665624006, +-0.012890781295031798, +-0.003848433944595686, +0.0052652470772714365, +0.014411458294166476, +0.023496859547180362, +0.032407735285352922, +0.041024636197531189, +0.049262803710663258, +0.057081426486627167, +0.0644432246130345, +0.071192130019287148, +0.077121705836652815, +0.082046565805285035, +0.085963174798727449, +0.088962099744073111, +0.091147643876155454, +0.092611697275091664, +0.0934343976062243, +0.093697151096349462, +0.093557087431308264, +0.093212531036278565, +0.092866344621457986, +0.0926231584831941, +0.092554864402990489, +0.09271878161671547, +0.09307509831648704, +0.093535130536602909, +0.094001491078051974, +0.094400779421826231, +0.094666082485034983, +0.094720751269154788, +0.094461905311396435, +0.093766737519417082, +0.092539571330352954, +0.090742777272945552, +0.0883859966055743, +0.085481710057628515, +0.082043300718181084, +0.078085310744849853, +0.073635495404436715, +0.06876724501260513, +0.063582771026592835, +0.058177946968049329, +0.052641058347472777, +0.047054072432297707, +0.04148818619100076, +0.035985481505104416, +0.030574986493929965, +0.025288898909317754, +0.020193458703052759, +0.015372150379206122, +0.010901525277439036, +0.0068222905455568288, +0.0031540685913691033, +-7.3678156771170462E-5, +-0.0027734473410175758, +-0.0048248080741077606, +-0.0061408501516516615, +-0.0068020363768584863, +-0.006983021293981745, +-0.0068552834175142664, +-0.0065163996406181861, +-0.0060224631002033652, +-0.0054353460270040186, +-0.0048686997800244, +-0.0044653849105144028, +-0.0043478819193246906, +-0.0045311812272728685, +-0.004969319488939113, +-0.0056123193635825262, +-0.0064326028677995388, +-0.0074153837397868475, +-0.0085456622322552071, +-0.0097990422699719242, +-0.011145768831928665, +-0.012560083824215262, +-0.014038753520541538, +-0.015591687642294488, +-0.017223535256183208, +-0.018905742108390643, +-0.020590424978343621, +-0.022233361857807308, +-0.023822339369596136, +-0.02536450628250532, +-0.026853966467348941, +-0.028210760544555381, +-0.02930942217925292, +-0.030036226436689649, +-0.030360301428596411, +-0.030303770117130591, +-0.029889509874320992, +-0.029103531102379648, +-0.027907937166776212, +-0.026283616637984245, +-0.024313612972540956, +-0.022147877509660237, +-0.019929975936662802, +-0.017726108377920304, +-0.015551077197925244, +-0.013403619553719614, +-0.011248182235655237, +-0.0090268249878619772, +-0.0066228166269453994, +-0.003952131972992874, +-0.0012011203213790872, +0.0017525471634552835, +0.0048951570485689377, +0.0081812965406557886, +0.011529255966025356, +0.014834058305330826, +0.017996656339090006, +0.020942558121807717, +0.023634282155959904, +0.02607567997386008, +0.028306505661839454, +0.030379275255314465, +0.032346494804483823, +0.034260294922665427, +0.036171747363461619, +0.038114259634342541, +0.040092718808342739, +0.042080859025593394, +0.04402702685648887, +0.045861926954884759, +0.047517603514654325, +0.04893783901866991, +0.050077810491081148, +0.050899229871005973, +0.051377957321346167, +0.051510516766029246, +0.051314704789312153, +0.050823337420800058, +0.050078286913036063, +0.049119074635726095, +0.047978017038116827, +0.046682222974873525, +0.045260301897983982, +0.043747010421930493, +0.042182683927508437, +0.040611233696758918, +0.03908138414602718, +0.037648088959401527, +0.036369362754778818, +0.035295378530927062, +0.034462507892582019, +0.0338869888547582, +0.033553168616274887, +0.033410126651247055, +0.033383629581289175, +0.03322349674281682, +0.03288366875602744, +0.032335741408496238, +0.031574375893814358, +0.030616193530210636, +0.029658011166606921, +0.028699828803003202, +0.02774164643939948, +0.026783464075795762, +0.025825281712192047, +0.024867099348588332, +0.02390891698498461, +0.022950734621380895, +0.021992552257777177, +0.021034369894173455, +0.02007618753056974, +0.019118005166966021, +0.018159822803362306, +0.017201640439758588, +0.016243458076154869, +0.015285275712551151, +0.014327093348947433, +0.013368910985343716, +0.012410728621739997, +0.011452546258136281, +0.010494363894532562, +0.0095361815309288438, +0.0085779991673251271, +0.0076198168037214095, +0.0066616344401176919, +0.0057034520765139735, +0.0047452697129102559, +0.0037870873493065387, +0.0028289049857028216, +0.0018707226220991034, +0.00091254025849538481, +-4.5642105108332988E-5, +-0.0010038244687120515, +-0.0019620068323157698, +-0.0029201891959194873, +-0.0038783715595232041, +-0.0048365539231269208, +-0.0057947362867306383, +-0.0067529186503343559, +-0.0077111010139380744, +-0.0086692833775417928, +-0.0096274657411455113, +-0.01058564810474923, +-0.011543830468352948, +-0.012502012831956665, +-0.013076922250118896, +-0.013460195195560383]} \ No newline at end of file From 80a3e27a84808180c039b65256cb6006c689d20a Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Fri, 11 Oct 2019 09:46:03 +0200 Subject: [PATCH 2/9] Fixed errors for PR --- PathPlanning/FrenetOptimalTrajectory/path_planner.py | 2 +- PathPlanning/FrenetOptimalTrajectory/racing_line.py | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index 53a9fe5ec9..83c9645001 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -382,7 +382,7 @@ def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): fplist = check_paths(fplist, ob) - if(len(fplist) == 0): + if not fplist: for i, _ in enumerate(fplist): if(fplist[i].s_d == 0): fplist = calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0) diff --git a/PathPlanning/FrenetOptimalTrajectory/racing_line.py b/PathPlanning/FrenetOptimalTrajectory/racing_line.py index fc1fdc9c2d..7523a6899c 100644 --- a/PathPlanning/FrenetOptimalTrajectory/racing_line.py +++ b/PathPlanning/FrenetOptimalTrajectory/racing_line.py @@ -22,21 +22,21 @@ def json_parser(self, json_file): o = data['Outside'] t = data['Inside'] p = data['Racing'] - for i in range(len(t)): + for i, _ in enumerate(t): d = t[i] n = d[0] m = d[1] ins_x.append(n) ins_y.append(m) - for j in range(len(o)): + for j, _ in enumerate(o): c = o[j] x = c[0] y = c[1] out_x.append(x) out_y.append(y) - for e in range(len(p)): + for e, _ in enumerate(p): if e%20 != 0: z = p[e] g = z[0] From ec2677e9e82245c71705501cd1ab5757078f626c Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Fri, 11 Oct 2019 10:29:16 +0200 Subject: [PATCH 3/9] Removed unused header --- .../FrenetOptimalTrajectory/path_planner.py | 45 +++++++++---------- .../FrenetOptimalTrajectory/racing_line.py | 7 +-- 2 files changed, 23 insertions(+), 29 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index 83c9645001..9e3587911f 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -234,36 +234,35 @@ def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0): # Longitudinal motion planning (Follow Mode) - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): - tfp = copy.deepcopy(fp) + tfp = copy.deepcopy(fp) - # calculate leading vehicle pos, vel, acc - s_lv1 = s0 + c_speed * Ti - s_lv1dot = c_speed - s_lv1ddot = 0 + # calculate leading vehicle pos, vel, acc + s_lv1 = s0 + c_speed * Ti + s_lv1dot = c_speed + s_lv1ddot = 0 - # calculate target pos, vel, acc - s_target = s_lv1 - (dist_safe + tau * s_lv1dot) - s_targetdot = s_lv1dot - s_targetddot = 0 - lon_qp = quintic_polynomial(s0, c_speed, 0.0, s_target, s_targetdot - 10.0, -10.0, Ti) + # calculate target pos, vel, acc + s_target = s_lv1 - (dist_safe + tau * s_lv1dot) + s_targetdot = s_lv1dot + s_targetddot = 0 + lon_qp = quintic_polynomial(s0, c_speed, 0.0, s_target, s_targetdot - 10.0, -10.0, Ti) - tfp.s = [lon_qp.calc_point(t) for t in fp.t] - tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] - tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] - tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + tfp.s = [lon_qp.calc_point(t) for t in fp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] - Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk - Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk + Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk + Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk - # square of diff from target speed - ds = (TARGET_SPEED - tfp.s_d[-1])**2 + # square of diff from target speed + ds = (TARGET_SPEED - tfp.s_d[-1])**2 - tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 - tfp.cv = KJ * Js + KT * Ti + KD * ds - tfp.cf = KLAT * tfp.cd + KLON * tfp.cv + tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 + tfp.cv = KJ * Js + KT * Ti + KD * ds + tfp.cf = KLAT * tfp.cd + KLON * tfp.cv - frenet_paths.append(tfp) + frenet_paths.append(tfp) return frenet_paths diff --git a/PathPlanning/FrenetOptimalTrajectory/racing_line.py b/PathPlanning/FrenetOptimalTrajectory/racing_line.py index 7523a6899c..f7d976f9e3 100644 --- a/PathPlanning/FrenetOptimalTrajectory/racing_line.py +++ b/PathPlanning/FrenetOptimalTrajectory/racing_line.py @@ -1,7 +1,5 @@ import sys from math import sqrt -import math -import os import numpy as np import json @@ -44,13 +42,10 @@ def json_parser(self, json_file): race_x.append(g) race_y.append(h) - - rx = np.array(race_x) - return race_x, race_y, ins_x, ins_y, out_x, out_y def curved_abscissa(self): - sum_partial = [] + c_a = [0] * len(self.race_x) for i in range(len(self.race_x)): From e57f20af01984baca57ccb933e921c8edb9cc219 Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Tue, 15 Oct 2019 13:10:19 +0200 Subject: [PATCH 4/9] fixed follow mode trigger conditions --- .../FrenetOptimalTrajectory/path_planner.py | 107 +++++++++++------- .../FrenetOptimalTrajectory/racing_line.py | 45 ++++---- 2 files changed, 93 insertions(+), 59 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index 9e3587911f..23e611ad23 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -30,19 +30,19 @@ MAX_ROAD_WIDTH = 7.0 # maximum road width [m] D_ROAD_W = 1.0 # road width sampling length [m] DT = 0.2 # time tick [s] -MAXT = 4.0 # max prediction time [m] +# MAXT = 4.0 # max prediction time [m] MINT = 2.0 # min prediction time [m] TARGET_SPEED = 60.0 / 3.6 # target speed [m/s] D_T_S = 10.0 / 3.6 # target speed sampling length [m/s] N_S_SAMPLE = 0.2 # sampling number of target speed -ROBOT_RADIUS = 1.0 # robot radius [m] +ROBOT_RADIUS = 2.0 # robot radius [m] # cost weights KJ = 0.1 KT = 0.1 -KD = 5.0 +KD = 1.0 KLAT = 5.0 -KLON = 1.0 +KLON = 3.0 show_animation = True @@ -166,8 +166,10 @@ def __init__(self): self.ds = [] self.c = [] + self.MAXT = 4.0 -def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): + +def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time): frenet_paths = [] @@ -175,7 +177,7 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): # Lateral motion planning - for Ti in np.arange(MINT, MAXT, DT): + for Ti in np.arange(MINT, pred_time, DT): fp = Frenet_path() lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) @@ -211,17 +213,19 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): return frenet_paths -def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0): +def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time, s0_target, c_speed_target): frenet_paths = [] - dist_safe = 20.0 - tau = 3.0 + dist_safe = 0.0 + tau = 2.0 + + print(pred_time) # generate path to each offset goal for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): # Lateral motion planning - for Ti in np.arange(MINT, MAXT, DT): + for Ti in np.arange(MINT, pred_time, DT): fp = Frenet_path() lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) @@ -237,15 +241,15 @@ def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0): tfp = copy.deepcopy(fp) # calculate leading vehicle pos, vel, acc - s_lv1 = s0 + c_speed * Ti - s_lv1dot = c_speed + s_lv1 = s0_target + c_speed_target * Ti + s_lv1dot = c_speed_target s_lv1ddot = 0 # calculate target pos, vel, acc s_target = s_lv1 - (dist_safe + tau * s_lv1dot) s_targetdot = s_lv1dot s_targetddot = 0 - lon_qp = quintic_polynomial(s0, c_speed, 0.0, s_target, s_targetdot - 10.0, -10.0, Ti) + lon_qp = quintic_polynomial(s0, c_speed, 0.0, s_target, s_targetdot, 0.0, Ti) tfp.s = [lon_qp.calc_point(t) for t in fp.t] tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] @@ -268,11 +272,11 @@ def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0): -def calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0): +def calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time): frenet_paths = [] # Longitudinal motion planning (Velocity keeping) - for Ti in np.arange(MINT, MAXT, DT): + for Ti in np.arange(MINT, pred_time, DT): tfp = Frenet_path() for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): @@ -361,39 +365,57 @@ def check_paths(fplist, ob): okind = [] for i, _ in enumerate(fplist): if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check + print("velocity") continue elif any([abs(a) > MAX_ACCEL for a in fplist[i].s_dd]): # Max accel check + print("acceleration") + print(fplist[i].s_dd) continue elif any([abs(c) > MAX_CURVATURE for c in fplist[i].c]): # Max curvature check + print("curvature") continue elif not check_collision(fplist[i], ob): + print("collision") continue okind.append(i) - - return [fplist[i] for i in okind] + print(len(okind)) -def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): + + return [fplist[i] for i in okind] - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) + print(len(okind)) - if not fplist: - for i, _ in enumerate(fplist): - if(fplist[i].s_d == 0): - fplist = calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) - else: - print("Follow Mode") - fplist = calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) + + return [fplist[i] for i in okind] +def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, pred_time, s0_target, c_speed_target): + + if(c_speed == 0.0): + print("###############") + print("Low Velocities") + print("###############") + fplist = calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + else: + print("###############") + print("Vel keeping") + print("###############") + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + if not fplist: + print("###############") + print("No trajectories, Follow Mode") + print("###############") + fplist = calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time, s0_target, c_speed_target) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + # find minimum cost path mincost = float("inf") bestpath = None @@ -404,9 +426,9 @@ def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): return bestpath -def frenet_optimal_planning_target(csp, s0, c_speed, c_d, c_d_d, c_d_dd): +def frenet_optimal_planning_target(csp, s0, c_speed, c_d, c_d_d, c_d_dd, pred_time): - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time) fplist = calc_global_paths(fplist, csp) # find minimum cost path @@ -438,7 +460,7 @@ def generate_target_course(x, y): def main(json_file): print(__file__ + " start!!") - rc = racing_line.RacingLine() + rc = racing_line.RacingLine rx,ry,insx,insy,outx,outy = rc.json_parser(json_file) @@ -470,7 +492,7 @@ def main(json_file): c_d_dd = 0.0 # current lateral acceleration [m/s] s0 = 0. # current course position - c_speed_target = 0.0 / 3.6 # current speed [m/s] + c_speed_target = 10.0 / 3.6 # current speed [m/s] c_d_target = 0.0 # current lateral position [m] c_d_d_target = 0.0 # current lateral speed [m/s] c_d_dd_target = 0.0 # current lateral acceleration [m/s] @@ -478,12 +500,14 @@ def main(json_file): area = 30.0 # animation area length [m] + pred_time = 4.0 + for i in range(SIM_LOOP): # start = time.time() path_target = frenet_optimal_planning_target(csp_target, s0_target, - c_speed_target, c_d_target, c_d_d_target, c_d_dd_target) + c_speed_target, c_d_target, c_d_d_target, c_d_dd_target, pred_time) ob_targetx.append(path_target.x[1]) ob_targety.append(path_target.y[1]) @@ -492,7 +516,8 @@ def main(json_file): path = frenet_optimal_planning( - csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target) + csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target, pred_time, \ + s0_target, c_speed_target) del ob_targetx[-1] del ob_targety[-1] @@ -522,12 +547,14 @@ def main(json_file): plt.plot(tx, ty) plt.plot(ob_target[0], ob_target[1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") - plt.plot(path.x[1], path.y[1], "vc") + # plt.plot(path.x[1], path.y[1], "vc") + circle = plt.Circle((path.x[1], path.y[1]), ROBOT_RADIUS, color='b', fill=False) + plt.gcf().gca().add_artist(circle) plt.plot(path_target.x[1:], path_target.y[1:], "-ob") plt.plot(path_target.x[1], path_target.y[1], "vc") plt.xlim(path.x[1] - area, path.x[1] + area) plt.ylim(path.y[1] - area, path.y[1] + area) - plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4] + " " + "vt[km/h]:" + str(c_speed_target * 3.6)[0:4]) + plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4] + " " + "vt[km/h]:" + str(c_speed_target * 3.6)[0:4] + " " + "a:" + str(path.s_dd[1])[0:4]) plt.grid(True) plt.pause(0.0001) diff --git a/PathPlanning/FrenetOptimalTrajectory/racing_line.py b/PathPlanning/FrenetOptimalTrajectory/racing_line.py index f7d976f9e3..d86eda252c 100644 --- a/PathPlanning/FrenetOptimalTrajectory/racing_line.py +++ b/PathPlanning/FrenetOptimalTrajectory/racing_line.py @@ -6,7 +6,7 @@ class RacingLine: - def json_parser(self, json_file): + def json_parser(json_file): race_x = [] race_y = [] @@ -21,38 +21,45 @@ def json_parser(self, json_file): t = data['Inside'] p = data['Racing'] for i, _ in enumerate(t): - d = t[i] - n = d[0] - m = d[1] - ins_x.append(n) - ins_y.append(m) + if i%10 == 0: + d = t[i] + n = d[0] + m = d[1] + ins_x.append(n) + ins_y.append(m) for j, _ in enumerate(o): - c = o[j] - x = c[0] - y = c[1] - out_x.append(x) - out_y.append(y) + if j%10 == 0: + c = o[j] + x = c[0] + y = c[1] + out_x.append(x) + out_y.append(y) for e, _ in enumerate(p): - if e%20 != 0: + if e%10 == 0: z = p[e] g = z[0] h = z[1] race_x.append(g) race_y.append(h) + # print(len(ins_x)) + return race_x, race_y, ins_x, ins_y, out_x, out_y - def curved_abscissa(self): + def curved_abscissa(x, y): - c_a = [0] * len(self.race_x) + c_a = [0] * len(x) - for i in range(len(self.race_x)): + for i in range(len(x)): if(i == 0): c_a[0] = 0 else: - c_a[i] = sqrt(pow(self.race_x[i] - self.race_x[i-1],2)+pow(self.race_y[i] - self.race_y[i-1],2)) + c_a[i-1] + c_a[i] = sqrt(pow(x[i] - x[i-1],2) + \ + pow(y[i] - y[i-1],2)) + c_a[i-1] + + # print(round(c_a[-1])) return c_a @@ -62,9 +69,9 @@ def print_usage(self): print('') def main(json_file): - rc = RacingLine() - rc.json_parser(json_file) - rc.curved_abscissa() + rc = RacingLine + a = rc.json_parser(json_file) + rc.curved_abscissa(a[0], a[1]) From 01d971b849dbb06bcf2daac39bb3d9c122540561 Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Tue, 15 Oct 2019 13:14:16 +0200 Subject: [PATCH 5/9] fixed errors pointed out from CodeFactor --- PathPlanning/FrenetOptimalTrajectory/path_planner.py | 3 --- PathPlanning/FrenetOptimalTrajectory/racing_line.py | 2 +- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index 23e611ad23..999709f014 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -379,9 +379,6 @@ def check_paths(fplist, ob): continue okind.append(i) - - print(len(okind)) - return [fplist[i] for i in okind] diff --git a/PathPlanning/FrenetOptimalTrajectory/racing_line.py b/PathPlanning/FrenetOptimalTrajectory/racing_line.py index d86eda252c..01ade8d749 100644 --- a/PathPlanning/FrenetOptimalTrajectory/racing_line.py +++ b/PathPlanning/FrenetOptimalTrajectory/racing_line.py @@ -52,7 +52,7 @@ def curved_abscissa(x, y): c_a = [0] * len(x) - for i in range(len(x)): + for i, _ in enumerate(x): if(i == 0): c_a[0] = 0 else: From 220a641c17f48333934ab3a72784e458fd836121 Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Tue, 15 Oct 2019 13:15:25 +0200 Subject: [PATCH 6/9] fixed errors pointed out from CodeFactor^2 --- PathPlanning/FrenetOptimalTrajectory/path_planner.py | 7 ------- 1 file changed, 7 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index 999709f014..c55e658f87 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -382,13 +382,6 @@ def check_paths(fplist, ob): return [fplist[i] for i in okind] - - print(len(okind)) - - - return [fplist[i] for i in okind] - - def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, pred_time, s0_target, c_speed_target): if(c_speed == 0.0): From 741ae22a011b7d031870c238a67ad36f6f839f73 Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Mon, 28 Oct 2019 11:15:24 +0100 Subject: [PATCH 7/9] extended frenet_optimal_trajectory.py functionalities --- .../frenet_optimal_trajectory.py | 294 ++++++++++++++---- .../FrenetOptimalTrajectory/racing_line.py | 7 +- 2 files changed, 231 insertions(+), 70 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 5c756a9dfe..a07dd0709d 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -17,32 +17,38 @@ import copy import math import cubic_spline_planner +import racing_line +import sys -SIM_LOOP = 500 +SIM_LOOP = 5000 # Parameter -MAX_SPEED = 50.0 / 3.6 # maximum speed [m/s] -MAX_ACCEL = 2.0 # maximum acceleration [m/ss] -MAX_CURVATURE = 1.0 # maximum curvature [1/m] -MAX_ROAD_WIDTH = 7.0 # maximum road width [m] -D_ROAD_W = 1.0 # road width sampling length [m] +MAX_SPEED = 60.0 / 3.6 # maximum speed [m/s] +MAX_ACCEL = 10.0 # maximum acceleration [m/ss] +MAX_CURVATURE = 100.0 # maximum curvature [1/m] +MAX_ROAD_WIDTH = 1.0 # maximum road width [m] +D_ROAD_W = 0.3 # road width sampling length [m] DT = 0.2 # time tick [s] -MAXT = 5.0 # max prediction time [m] -MINT = 4.0 # min prediction time [m] -TARGET_SPEED = 30.0 / 3.6 # target speed [m/s] -D_T_S = 5.0 / 3.6 # target speed sampling length [m/s] -N_S_SAMPLE = 1 # sampling number of target speed +MAXT = 4.0 # max prediction time [m] +MINT = 2.0 # min prediction time [m] +TARGET_SPEED = 60.0 / 3.6 # target speed [m/s] +D_T_S = 10.0 / 3.6 # target speed sampling length [m/s] +N_S_SAMPLE = 0.2 # sampling number of target speed ROBOT_RADIUS = 2.0 # robot radius [m] # cost weights KJ = 0.1 KT = 0.1 KD = 1.0 -KLAT = 1.0 -KLON = 1.0 +KLAT = 5.0 +KLON = 3.0 -show_animation = True +low_velocity = False +follow_mode = False +velocity_keeping = False + +show_animation = True class quintic_polynomial: @@ -165,29 +171,117 @@ def __init__(self): self.c = [] -def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): +def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target): frenet_paths = [] + dist_safe = 0.0 + tau = 2.0 - # generate path to each offset goal - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - - # Lateral motion planning + if low_velocity: + # Longitudinal motion planning for Ti in np.arange(MINT, MAXT, DT): - fp = Frenet_path() + tfp = Frenet_path() - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) - fp.t = [t for t in np.arange(0.0, Ti, DT)] - fp.d = [lat_qp.calc_point(t) for t in fp.t] - fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] - fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] - fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + tfp.t = [t for t in np.arange(0.0, Ti, DT)] + tfp.s = [lon_qp.calc_point(t) for t in tfp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in tfp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in tfp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in tfp.t] - # Loongitudinal motion planning (Velocity keeping) - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + # Lateral motion planning + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + + fp = copy.deepcopy(tfp) + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + + fp.d = [lat_qp.calc_point(s) for s in tfp.s] + fp.d_d = [lat_qp.calc_first_derivative(s) for s in tfp.s] + fp.d_dd = [lat_qp.calc_second_derivative(s) for s in tfp.s] + fp.d_ddd = [lat_qp.calc_third_derivative(s) for s in tfp.s] + + Jp = sum(np.power(fp.d_ddd, 2)) # square of jerk + Js = sum(np.power(fp.s_ddd, 2)) # square of jerk + + # square of diff from target speed + ds = (TARGET_SPEED - tfp.s_d[-1])**2 + + fp.cd = KJ * Jp + KT * Ti + KD * fp.d[-1]**2 + fp.cv = KJ * Js + KT * Ti + KD * ds + fp.cf = KLAT * fp.cd + KLON * fp.cv + + frenet_paths.append(fp) + + if velocity_keeping: + # generate path to each offset goal + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + + # Lateral motion planning + for Ti in np.arange(MINT, MAXT, DT): + fp = Frenet_path() + + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.d = [lat_qp.calc_point(t) for t in fp.t] + fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] + fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] + fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + + # Longitudinal motion planning + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + tfp = copy.deepcopy(fp) + lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + + tfp.s = [lon_qp.calc_point(t) for t in fp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + + Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk + Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk + + # square of diff from target speed + ds = (TARGET_SPEED - tfp.s_d[-1])**2 + + tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 + tfp.cv = KJ * Js + KT * Ti + KD * ds + tfp.cf = KLAT * tfp.cd + KLON * tfp.cv + + frenet_paths.append(tfp) + + if follow_mode: + # generate path to each offset goal + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + + # Lateral motion planning + for Ti in np.arange(MINT, MAXT, DT): + fp = Frenet_path() + + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.d = [lat_qp.calc_point(t) for t in fp.t] + fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] + fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] + fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + + + # Longitudinal motion planning tfp = copy.deepcopy(fp) - lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + + # calculate leading vehicle pos, vel, acc + s_lv1 = s0_target + c_speed_target * Ti + s_lv1dot = c_speed_target + s_lv1ddot = 0.0 + + # calculate target pos, vel, acc + s_target = s_lv1 - (dist_safe + tau * s_lv1dot) + s_targetdot = s_lv1dot + s_targetddot = 0.0 + lon_qp = quintic_polynomial(s0, c_speed, s_lv1ddot, s_target, s_targetdot, s_targetddot, Ti) tfp.s = [lon_qp.calc_point(t) for t in fp.t] tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] @@ -205,7 +299,7 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): tfp.cf = KLAT * tfp.cd + KLON * tfp.cv frenet_paths.append(tfp) - + return frenet_paths @@ -244,14 +338,13 @@ def calc_global_paths(fplist, csp): def check_collision(fp, ob): - for i in range(len(ob[:, 0])): - d = [((ix - ob[i, 0])**2 + (iy - ob[i, 1])**2) - for (ix, iy) in zip(fp.x, fp.y)] + d = [((ix - ob[0])**2 + (iy - ob[1])**2) + for (ix, iy) in zip(fp.x, fp.y)] - collision = any([di <= ROBOT_RADIUS**2 for di in d]) + collision = np.any([di <= ROBOT_RADIUS**2 for di in d]) - if collision: - return False + if collision: + return False return True @@ -270,16 +363,41 @@ def check_paths(fplist, ob): continue okind.append(i) - + return [fplist[i] for i in okind] - -def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): - - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) - +def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, s0_target, c_speed_target): + + global low_velocity, velocity_keeping, follow_mode + + if(c_speed == 0.0): + low_velocity = True + velocity_keeping = False + follow_mode = False + print("###############") + print("Low Velocities") + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, 0.0, 0.0) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + else: + low_velocity = False + velocity_keeping = True + follow_mode = False + print("###############") + print("Velocity keeping") + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, 0.0, 0.0) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + if not fplist: + low_velocity = False + velocity_keeping = False + follow_mode = True + print("###############") + print("No trajectories, Follow Mode") + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + # find minimum cost path mincost = float("inf") bestpath = None @@ -306,34 +424,64 @@ def generate_target_course(x, y): return rx, ry, ryaw, rk, csp -def main(): +def main(json_file): print(__file__ + " start!!") - # way points - wx = [0.0, 10.0, 20.5, 35.0, 70.5] - wy = [0.0, -6.0, 5.0, 6.5, 0.0] - # obstacle lists - ob = np.array([[20.0, 10.0], - [30.0, 6.0], - [30.0, 8.0], - [35.0, 8.0], - [50.0, 3.0] - ]) + rc = racing_line.RacingLine() + + rx,ry,insx,insy,outx,outy = rc.json_parser(json_file) + + + num_laps = 3 + wx, wy, targetx, targety = [], [], [], [] + + for i in range(num_laps): + wx.extend(rx) + wy.extend(ry) + targetx.extend(rx) + targety.extend(ry) + + borders_x = insx + borders_y = insy + borders_x.extend(outx) + borders_y.extend(outy) + + ob_targetx = borders_x + ob_targety = borders_y + + ob_borders = np.array([borders_x, borders_y]) tx, ty, tyaw, tc, csp = generate_target_course(wx, wy) + tx_target, ty_target, tyaw_target, tc_target, csp_target = generate_target_course(targetx, targety) # initial state - c_speed = 10.0 / 3.6 # current speed [m/s] - c_d = 2.0 # current lateral position [m] + c_speed = 0.0 / 3.6 # current speed [m/s] + c_d = 0.0 # current lateral position [m] c_d_d = 0.0 # current lateral speed [m/s] - c_d_dd = 0.0 # current latral acceleration [m/s] + c_d_dd = 0.0 # current lateral acceleration [m/s] s0 = 0.0 # current course position - area = 20.0 # animation area length [m] + c_speed_target = 10.0 / 3.6 # current speed [m/s] + c_d_target = 0.0 # current lateral position [m] + c_d_d_target = 0.0 # current lateral speed [m/s] + c_d_dd_target = 0.0 # current lateral acceleration [m/s] + s0_target = 50.0 # current course position + + area = 30.0 # animation area length [m] for i in range(SIM_LOOP): - path = frenet_optimal_planning( - csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob) + + path_target = frenet_optimal_planning(csp_target, s0_target, c_speed_target, c_d_target, c_d_d_target, c_d_dd_target, ob_borders, 0.0, 0.0) + + ob_targetx.append(path_target.x[1]) + ob_targety.append(path_target.y[1]) + + ob_target = np.array([ob_targetx,ob_targety]) + + path = frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target, s0_target, c_speed_target) + + del ob_targetx[-1] + del ob_targety[-1] s0 = path.s[1] c_d = path.d[1] @@ -341,22 +489,36 @@ def main(): c_d_dd = path.d_dd[1] c_speed = path.s_d[1] - if np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0: + s0_target = path_target.s[1] + c_d_target = path_target.d[1] + c_d_d_target = path_target.d_d[1] + c_d_dd_target = path_target.d_dd[1] + c_speed_target = path_target.s_d[1] + + + if(path_target.s_d[1] >= 11.0): + c_speed_target = 10.0 + + if (np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0) and (np.hypot(path_target.x[1] - tx_target[-1], path_target.y[1] - ty_target[-1]) <= 1.0): print("Goal") break if show_animation: # pragma: no cover plt.cla() plt.plot(tx, ty) - plt.plot(ob[:, 0], ob[:, 1], "xk") + plt.plot(ob_target[0], ob_target[1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") - plt.plot(path.x[1], path.y[1], "vc") + circle = plt.Circle((path.x[1], path.y[1]), ROBOT_RADIUS, color='b', fill=False) + plt.gcf().gca().add_artist(circle) + plt.plot(path_target.x[1:], path_target.y[1:], "-ob") + plt.plot(path_target.x[1], path_target.y[1], "vc") plt.xlim(path.x[1] - area, path.x[1] + area) plt.ylim(path.y[1] - area, path.y[1] + area) - plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4]) + plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4] + " " + "vt[km/h]:" + str(c_speed_target * 3.6)[0:4] + " " + "a:" + str(path.s_dd[1])[0:4]) plt.grid(True) plt.pause(0.0001) + print("Finish") if show_animation: # pragma: no cover plt.grid(True) @@ -365,4 +527,4 @@ def main(): if __name__ == '__main__': - main() + main(sys.argv[1]) diff --git a/PathPlanning/FrenetOptimalTrajectory/racing_line.py b/PathPlanning/FrenetOptimalTrajectory/racing_line.py index 01ade8d749..4d2f1f9152 100644 --- a/PathPlanning/FrenetOptimalTrajectory/racing_line.py +++ b/PathPlanning/FrenetOptimalTrajectory/racing_line.py @@ -1,12 +1,11 @@ import sys from math import sqrt -import numpy as np import json class RacingLine: - def json_parser(json_file): + def json_parser(self, json_file): race_x = [] race_y = [] @@ -48,7 +47,7 @@ def json_parser(json_file): return race_x, race_y, ins_x, ins_y, out_x, out_y - def curved_abscissa(x, y): + def curved_abscissa(self, x, y): c_a = [0] * len(x) @@ -69,7 +68,7 @@ def print_usage(self): print('') def main(json_file): - rc = RacingLine + rc = RacingLine() a = rc.json_parser(json_file) rc.curved_abscissa(a[0], a[1]) From b23f1fc01b2e81fd9fd57dce8414c2f8aef1b992 Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Tue, 29 Oct 2019 10:15:11 +0100 Subject: [PATCH 8/9] testing on codefactor.io --- .../frenet_optimal_trajectory.py | 257 +++--------- .../FrenetOptimalTrajectory/path_planner.py | 395 +++--------------- 2 files changed, 108 insertions(+), 544 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index a07dd0709d..b49c553b60 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -17,8 +17,6 @@ import copy import math import cubic_spline_planner -import racing_line -import sys SIM_LOOP = 5000 @@ -43,13 +41,9 @@ KLAT = 5.0 KLON = 3.0 - -low_velocity = False -follow_mode = False -velocity_keeping = False - show_animation = True + class quintic_polynomial: def __init__(self, xs, vxs, axs, xe, vxe, axe, T): @@ -171,117 +165,29 @@ def __init__(self): self.c = [] -def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target): +def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): frenet_paths = [] - dist_safe = 0.0 - tau = 2.0 - - if low_velocity: - # Longitudinal motion planning - for Ti in np.arange(MINT, MAXT, DT): - tfp = Frenet_path() - - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): - lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) - - tfp.t = [t for t in np.arange(0.0, Ti, DT)] - tfp.s = [lon_qp.calc_point(t) for t in tfp.t] - tfp.s_d = [lon_qp.calc_first_derivative(t) for t in tfp.t] - tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in tfp.t] - tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in tfp.t] - - # Lateral motion planning - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - - fp = copy.deepcopy(tfp) - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - - fp.d = [lat_qp.calc_point(s) for s in tfp.s] - fp.d_d = [lat_qp.calc_first_derivative(s) for s in tfp.s] - fp.d_dd = [lat_qp.calc_second_derivative(s) for s in tfp.s] - fp.d_ddd = [lat_qp.calc_third_derivative(s) for s in tfp.s] - - Jp = sum(np.power(fp.d_ddd, 2)) # square of jerk - Js = sum(np.power(fp.s_ddd, 2)) # square of jerk - - # square of diff from target speed - ds = (TARGET_SPEED - tfp.s_d[-1])**2 - fp.cd = KJ * Jp + KT * Ti + KD * fp.d[-1]**2 - fp.cv = KJ * Js + KT * Ti + KD * ds - fp.cf = KLAT * fp.cd + KLON * fp.cv + # generate path to each offset goal + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - frenet_paths.append(fp) - - if velocity_keeping: - # generate path to each offset goal - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - - # Lateral motion planning - for Ti in np.arange(MINT, MAXT, DT): - fp = Frenet_path() - - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - - fp.t = [t for t in np.arange(0.0, Ti, DT)] - fp.d = [lat_qp.calc_point(t) for t in fp.t] - fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] - fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] - fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] - - # Longitudinal motion planning - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): - tfp = copy.deepcopy(fp) - lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) - - tfp.s = [lon_qp.calc_point(t) for t in fp.t] - tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] - tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] - tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] - - Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk - Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk - - # square of diff from target speed - ds = (TARGET_SPEED - tfp.s_d[-1])**2 - - tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 - tfp.cv = KJ * Js + KT * Ti + KD * ds - tfp.cf = KLAT * tfp.cd + KLON * tfp.cv - - frenet_paths.append(tfp) - - if follow_mode: - # generate path to each offset goal - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - - # Lateral motion planning - for Ti in np.arange(MINT, MAXT, DT): - fp = Frenet_path() + # Lateral motion planning + for Ti in np.arange(MINT, MAXT, DT): + fp = Frenet_path() - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - fp.t = [t for t in np.arange(0.0, Ti, DT)] - fp.d = [lat_qp.calc_point(t) for t in fp.t] - fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] - fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] - fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.d = [lat_qp.calc_point(t) for t in fp.t] + fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] + fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] + fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] - - # Longitudinal motion planning + # Loongitudinal motion planning (Velocity keeping) + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): tfp = copy.deepcopy(fp) - - # calculate leading vehicle pos, vel, acc - s_lv1 = s0_target + c_speed_target * Ti - s_lv1dot = c_speed_target - s_lv1ddot = 0.0 - - # calculate target pos, vel, acc - s_target = s_lv1 - (dist_safe + tau * s_lv1dot) - s_targetdot = s_lv1dot - s_targetddot = 0.0 - lon_qp = quintic_polynomial(s0, c_speed, s_lv1ddot, s_target, s_targetdot, s_targetddot, Ti) + lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) tfp.s = [lon_qp.calc_point(t) for t in fp.t] tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] @@ -299,7 +205,7 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target tfp.cf = KLAT * tfp.cd + KLON * tfp.cv frenet_paths.append(tfp) - + return frenet_paths @@ -363,41 +269,16 @@ def check_paths(fplist, ob): continue okind.append(i) - + return [fplist[i] for i in okind] -def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, s0_target, c_speed_target): - - global low_velocity, velocity_keeping, follow_mode - - if(c_speed == 0.0): - low_velocity = True - velocity_keeping = False - follow_mode = False - print("###############") - print("Low Velocities") - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, 0.0, 0.0) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) - else: - low_velocity = False - velocity_keeping = True - follow_mode = False - print("###############") - print("Velocity keeping") - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, 0.0, 0.0) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) - if not fplist: - low_velocity = False - velocity_keeping = False - follow_mode = True - print("###############") - print("No trajectories, Follow Mode") - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) - + +def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): + + fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = calc_global_paths(fplist, csp) + fplist = check_paths(fplist, ob) + # find minimum cost path mincost = float("inf") bestpath = None @@ -424,64 +305,34 @@ def generate_target_course(x, y): return rx, ry, ryaw, rk, csp -def main(json_file): +def main(): print(__file__ + " start!!") - rc = racing_line.RacingLine() - - rx,ry,insx,insy,outx,outy = rc.json_parser(json_file) - - - num_laps = 3 - wx, wy, targetx, targety = [], [], [], [] - - for i in range(num_laps): - wx.extend(rx) - wy.extend(ry) - targetx.extend(rx) - targety.extend(ry) - - borders_x = insx - borders_y = insy - borders_x.extend(outx) - borders_y.extend(outy) - - ob_targetx = borders_x - ob_targety = borders_y - - ob_borders = np.array([borders_x, borders_y]) + # way points + wx = [0.0, 10.0, 20.5, 35.0, 70.5] + wy = [0.0, -6.0, 5.0, 6.5, 0.0] + # obstacle lists + obx = [20.0, 30.0, 30.0, 35.0, 50.0] + oby = [10.0, 6.0, 8.0, 8.0, 3.0] + + ob = np.array([obx,oby]) + + print(ob[:]) tx, ty, tyaw, tc, csp = generate_target_course(wx, wy) - tx_target, ty_target, tyaw_target, tc_target, csp_target = generate_target_course(targetx, targety) # initial state - c_speed = 0.0 / 3.6 # current speed [m/s] - c_d = 0.0 # current lateral position [m] + c_speed = 10.0 / 3.6 # current speed [m/s] + c_d = 2.0 # current lateral position [m] c_d_d = 0.0 # current lateral speed [m/s] - c_d_dd = 0.0 # current lateral acceleration [m/s] + c_d_dd = 0.0 # current latral acceleration [m/s] s0 = 0.0 # current course position - c_speed_target = 10.0 / 3.6 # current speed [m/s] - c_d_target = 0.0 # current lateral position [m] - c_d_d_target = 0.0 # current lateral speed [m/s] - c_d_dd_target = 0.0 # current lateral acceleration [m/s] - s0_target = 50.0 # current course position - - area = 30.0 # animation area length [m] + area = 40.0 # animation area length [m] for i in range(SIM_LOOP): - - path_target = frenet_optimal_planning(csp_target, s0_target, c_speed_target, c_d_target, c_d_d_target, c_d_dd_target, ob_borders, 0.0, 0.0) - - ob_targetx.append(path_target.x[1]) - ob_targety.append(path_target.y[1]) - - ob_target = np.array([ob_targetx,ob_targety]) - - path = frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target, s0_target, c_speed_target) - - del ob_targetx[-1] - del ob_targety[-1] + path = frenet_optimal_planning( + csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob) s0 = path.s[1] c_d = path.d[1] @@ -489,36 +340,22 @@ def main(json_file): c_d_dd = path.d_dd[1] c_speed = path.s_d[1] - s0_target = path_target.s[1] - c_d_target = path_target.d[1] - c_d_d_target = path_target.d_d[1] - c_d_dd_target = path_target.d_dd[1] - c_speed_target = path_target.s_d[1] - - - if(path_target.s_d[1] >= 11.0): - c_speed_target = 10.0 - - if (np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0) and (np.hypot(path_target.x[1] - tx_target[-1], path_target.y[1] - ty_target[-1]) <= 1.0): + if np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0: print("Goal") break if show_animation: # pragma: no cover plt.cla() plt.plot(tx, ty) - plt.plot(ob_target[0], ob_target[1], "xk") + plt.plot(ob[0], ob[1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") - circle = plt.Circle((path.x[1], path.y[1]), ROBOT_RADIUS, color='b', fill=False) - plt.gcf().gca().add_artist(circle) - plt.plot(path_target.x[1:], path_target.y[1:], "-ob") - plt.plot(path_target.x[1], path_target.y[1], "vc") + plt.plot(path.x[1], path.y[1], "vc") plt.xlim(path.x[1] - area, path.x[1] + area) plt.ylim(path.y[1] - area, path.y[1] + area) - plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4] + " " + "vt[km/h]:" + str(c_speed_target * 3.6)[0:4] + " " + "a:" + str(path.s_dd[1])[0:4]) + plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4]) plt.grid(True) plt.pause(0.0001) - print("Finish") if show_animation: # pragma: no cover plt.grid(True) @@ -527,4 +364,4 @@ def main(json_file): if __name__ == '__main__': - main(sys.argv[1]) + main() diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index c55e658f87..10b96e3b55 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -19,7 +19,8 @@ import cubic_spline_planner import racing_line import sys -import time + +import frenet_optimal_trajectory SIM_LOOP = 5000 @@ -30,7 +31,7 @@ MAX_ROAD_WIDTH = 7.0 # maximum road width [m] D_ROAD_W = 1.0 # road width sampling length [m] DT = 0.2 # time tick [s] -# MAXT = 4.0 # max prediction time [m] +MAXT = 4.0 # max prediction time [m] MINT = 2.0 # min prediction time [m] TARGET_SPEED = 60.0 / 3.6 # target speed [m/s] D_T_S = 10.0 / 3.6 # target speed sampling length [m/s] @@ -44,191 +45,67 @@ KLAT = 5.0 KLON = 3.0 -show_animation = True - -class quintic_polynomial: - - def __init__(self, xs, vxs, axs, xe, vxe, axe, T): - - # calc coefficient of quintic polynomial - self.xs = xs - self.vxs = vxs - self.axs = axs - self.xe = xe - self.vxe = vxe - self.axe = axe - - self.a0 = xs - self.a1 = vxs - self.a2 = axs / 2.0 - - A = np.array([[T**3, T**4, T**5], - [3 * T ** 2, 4 * T ** 3, 5 * T ** 4], - [6 * T, 12 * T ** 2, 20 * T ** 3]]) - b = np.array([xe - self.a0 - self.a1 * T - self.a2 * T**2, - vxe - self.a1 - 2 * self.a2 * T, - axe - 2 * self.a2]) - x = np.linalg.solve(A, b) - - self.a3 = x[0] - self.a4 = x[1] - self.a5 = x[2] - - def calc_point(self, t): - xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ - self.a3 * t**3 + self.a4 * t**4 + self.a5 * t**5 - - return xt - - def calc_first_derivative(self, t): - xt = self.a1 + 2 * self.a2 * t + \ - 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 5 * self.a5 * t**4 - - return xt - - def calc_second_derivative(self, t): - xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + 20 * self.a5 * t**3 - - return xt - - def calc_third_derivative(self, t): - xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t**2 - - return xt - - -class quartic_polynomial: - def __init__(self, xs, vxs, axs, vxe, axe, T): - - # calc coefficient of quintic polynomial - self.xs = xs - self.vxs = vxs - self.axs = axs - self.vxe = vxe - self.axe = axe - - self.a0 = xs - self.a1 = vxs - self.a2 = axs / 2.0 - - A = np.array([[3 * T ** 2, 4 * T ** 3], - [6 * T, 12 * T ** 2]]) - b = np.array([vxe - self.a1 - 2 * self.a2 * T, - axe - 2 * self.a2]) - x = np.linalg.solve(A, b) - - self.a3 = x[0] - self.a4 = x[1] - - def calc_point(self, t): - xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ - self.a3 * t**3 + self.a4 * t**4 - - return xt - - def calc_first_derivative(self, t): - xt = self.a1 + 2 * self.a2 * t + \ - 3 * self.a3 * t**2 + 4 * self.a4 * t**3 - - return xt - - def calc_second_derivative(self, t): - xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 - - return xt - - def calc_third_derivative(self, t): - xt = 6 * self.a3 + 24 * self.a4 * t - - return xt - - -class Frenet_path: - - def __init__(self): - self.t = [] - self.d = [] - self.d_d = [] - self.d_dd = [] - self.d_ddd = [] - self.s = [] - self.s_d = [] - self.s_dd = [] - self.s_ddd = [] - self.cd = 0.0 - self.cv = 0.0 - self.cf = 0.0 - - self.x = [] - self.y = [] - self.yaw = [] - self.ds = [] - self.c = [] +show_animation = True - self.MAXT = 4.0 -def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time): +def calc_frenet_paths_lv(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target): # Low velocities frenet_paths = [] - # generate path to each offset goal - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): + # Longitudinal motion planning + for Ti in np.arange(MINT, MAXT, DT): + tfp = frenet_optimal_trajectory.Frenet_path() - # Lateral motion planning - for Ti in np.arange(MINT, pred_time, DT): - fp = Frenet_path() + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + lon_qp = frenet_optimal_trajectory.quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + tfp.t = [t for t in np.arange(0.0, Ti, DT)] + tfp.s = [lon_qp.calc_point(t) for t in tfp.t] + tfp.s_d = [lon_qp.calc_first_derivative(t) for t in tfp.t] + tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in tfp.t] + tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in tfp.t] - fp.t = [t for t in np.arange(0.0, Ti, DT)] - fp.d = [lat_qp.calc_point(t) for t in fp.t] - fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] - fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] - fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] + # Lateral motion planning + for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - # Longitudinal motion planning (Velocity keeping) - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): - tfp = copy.deepcopy(fp) - lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + fp = copy.deepcopy(tfp) + lat_qp = frenet_optimal_trajectory.quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - tfp.s = [lon_qp.calc_point(t) for t in fp.t] - tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] - tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] - tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + fp.d = [lat_qp.calc_point(s) for s in tfp.s] + fp.d_d = [lat_qp.calc_first_derivative(s) for s in tfp.s] + fp.d_dd = [lat_qp.calc_second_derivative(s) for s in tfp.s] + fp.d_ddd = [lat_qp.calc_third_derivative(s) for s in tfp.s] - Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk - Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk + Jp = sum(np.power(fp.d_ddd, 2)) # square of jerk + Js = sum(np.power(fp.s_ddd, 2)) # square of jerk # square of diff from target speed ds = (TARGET_SPEED - tfp.s_d[-1])**2 - tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 - tfp.cv = KJ * Js + KT * Ti + KD * ds - tfp.cf = KLAT * tfp.cd + KLON * tfp.cv + fp.cd = KJ * Jp + KT * Ti + KD * fp.d[-1]**2 + fp.cv = KJ * Js + KT * Ti + KD * ds + fp.cf = KLAT * fp.cd + KLON * fp.cv - frenet_paths.append(tfp) - - return frenet_paths + frenet_paths.append(fp) + return frenet_paths -def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time, s0_target, c_speed_target): +def calc_frenet_paths_fm(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target): # Follow mode frenet_paths = [] dist_safe = 0.0 tau = 2.0 - - print(pred_time) - + # generate path to each offset goal for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): # Lateral motion planning - for Ti in np.arange(MINT, pred_time, DT): - fp = Frenet_path() + for Ti in np.arange(MINT, MAXT, DT): + fp = frenet_optimal_trajectory.Frenet_path() - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + lat_qp = frenet_optimal_trajectory.quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) fp.t = [t for t in np.arange(0.0, Ti, DT)] fp.d = [lat_qp.calc_point(t) for t in fp.t] @@ -237,19 +114,19 @@ def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time, s0 fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] - # Longitudinal motion planning (Follow Mode) + # Longitudinal motion planning tfp = copy.deepcopy(fp) # calculate leading vehicle pos, vel, acc s_lv1 = s0_target + c_speed_target * Ti s_lv1dot = c_speed_target - s_lv1ddot = 0 + s_lv1ddot = 0.0 # calculate target pos, vel, acc s_target = s_lv1 - (dist_safe + tau * s_lv1dot) s_targetdot = s_lv1dot - s_targetddot = 0 - lon_qp = quintic_polynomial(s0, c_speed, 0.0, s_target, s_targetdot, 0.0, Ti) + s_targetddot = 0.0 + lon_qp = frenet_optimal_trajectory.quintic_polynomial(s0, c_speed, s_lv1ddot, s_target, s_targetdot, s_targetddot, Ti) tfp.s = [lon_qp.calc_point(t) for t in fp.t] tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] @@ -267,144 +144,32 @@ def calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time, s0 tfp.cf = KLAT * tfp.cd + KLON * tfp.cv frenet_paths.append(tfp) - + return frenet_paths -def calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time): - frenet_paths = [] - - # Longitudinal motion planning (Velocity keeping) - for Ti in np.arange(MINT, pred_time, DT): - tfp = Frenet_path() +def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, s0_target, c_speed_target): - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): - lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) - - tfp.t = [t for t in np.arange(0.0, Ti, DT)] - tfp.s = [lon_qp.calc_point(t) for t in tfp.t] - tfp.s_d = [lon_qp.calc_first_derivative(t) for t in tfp.t] - tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in tfp.t] - tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in tfp.t] - - # Lateral motion planning - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - - fp = copy.deepcopy(tfp) - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - - fp.d = [lat_qp.calc_point(s) for s in tfp.s] - fp.d_d = [lat_qp.calc_first_derivative(s) for s in tfp.s] - fp.d_dd = [lat_qp.calc_second_derivative(s) for s in tfp.s] - fp.d_ddd = [lat_qp.calc_third_derivative(s) for s in tfp.s] - - Jp = sum(np.power(fp.d_ddd, 2)) # square of jerk - Js = sum(np.power(fp.s_ddd, 2)) # square of jerk - - # square of diff from target speed - ds = (TARGET_SPEED - tfp.s_d[-1])**2 - - fp.cd = KJ * Jp + KT * Ti + KD * fp.d[-1]**2 - fp.cv = KJ * Js + KT * Ti + KD * ds - fp.cf = KLAT * fp.cd + KLON * fp.cv - - frenet_paths.append(fp) - - return frenet_paths - - -def calc_global_paths(fplist, csp): - - for fp in fplist: - - # calc global positions - for i in range(len(fp.s)): - ix, iy = csp.calc_position(fp.s[i]) - if ix is None: - break - iyaw = csp.calc_yaw(fp.s[i]) - di = fp.d[i] - fx = ix + di * math.cos(iyaw + math.pi / 2.0) - fy = iy + di * math.sin(iyaw + math.pi / 2.0) - fp.x.append(fx) - fp.y.append(fy) - - # calc yaw and ds - for i in range(len(fp.x) - 1): - dx = fp.x[i + 1] - fp.x[i] - dy = fp.y[i + 1] - fp.y[i] - fp.yaw.append(math.atan2(dy, dx)) - fp.ds.append(math.sqrt(dx**2 + dy**2)) - - fp.yaw.append(fp.yaw[-1]) - fp.ds.append(fp.ds[-1]) - - # calc curvature - for i in range(len(fp.yaw) - 1): - fp.c.append((fp.yaw[i + 1] - fp.yaw[i]) / fp.ds[i]) - - return fplist - - -def check_collision(fp, ob): - - d = [((ix - ob[0])**2 + (iy - ob[1])**2) - for (ix, iy) in zip(fp.x, fp.y)] - - collision = np.any([di <= ROBOT_RADIUS**2 for di in d]) - - if collision: - return False - - return True - - -def check_paths(fplist, ob): - - okind = [] - for i, _ in enumerate(fplist): - if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check - print("velocity") - continue - elif any([abs(a) > MAX_ACCEL for a in fplist[i].s_dd]): # Max accel check - print("acceleration") - print(fplist[i].s_dd) - continue - elif any([abs(c) > MAX_CURVATURE for c in fplist[i].c]): # Max curvature check - print("curvature") - continue - elif not check_collision(fplist[i], ob): - print("collision") - continue - - okind.append(i) - - return [fplist[i] for i in okind] - -def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, pred_time, s0_target, c_speed_target): if(c_speed == 0.0): print("###############") print("Low Velocities") - print("###############") - fplist = calc_frenet_paths_low_velocity(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) + fplist = calc_frenet_paths_lv(c_speed, c_d, c_d_d, c_d_dd, s0, 0.0, 0.0) + fplist = frenet_optimal_trajectory.calc_global_paths(fplist, csp) + fplist = frenet_optimal_trajectory.check_paths(fplist, ob) else: print("###############") - print("Vel keeping") - print("###############") - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) + print("Velocity keeping") + fplist = frenet_optimal_trajectory.calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) + fplist = frenet_optimal_trajectory.calc_global_paths(fplist, csp) + fplist = frenet_optimal_trajectory.check_paths(fplist, ob) if not fplist: print("###############") print("No trajectories, Follow Mode") - print("###############") - fplist = calc_frenet_paths_follow_mode(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time, s0_target, c_speed_target) - fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) + fplist = calc_frenet_paths_fm(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target) + fplist = frenet_optimal_trajectory.calc_global_paths(fplist, csp) + fplist = frenet_optimal_trajectory.check_paths(fplist, ob) # find minimum cost path mincost = float("inf") @@ -416,41 +181,13 @@ def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, pred_time, return bestpath -def frenet_optimal_planning_target(csp, s0, c_speed, c_d, c_d_d, c_d_dd, pred_time): - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0, pred_time) - fplist = calc_global_paths(fplist, csp) - - # find minimum cost path - mincost = float("inf") - bestpath = None - for fp in fplist: - if mincost >= fp.cf: - mincost = fp.cf - bestpath = fp - - return bestpath - - -def generate_target_course(x, y): - csp = cubic_spline_planner.Spline2D(x, y) - s = np.arange(0, csp.s[-1], 0.1) - - rx, ry, ryaw, rk = [], [], [], [] - for i_s in s: - ix, iy = csp.calc_position(i_s) - rx.append(ix) - ry.append(iy) - ryaw.append(csp.calc_yaw(i_s)) - rk.append(csp.calc_curvature(i_s)) - - return rx, ry, ryaw, rk, csp def main(json_file): print(__file__ + " start!!") - rc = racing_line.RacingLine + rc = racing_line.RacingLine() rx,ry,insx,insy,outx,outy = rc.json_parser(json_file) @@ -472,17 +209,19 @@ def main(json_file): ob_targetx = borders_x ob_targety = borders_y - tx, ty, tyaw, tc, csp = generate_target_course(wx, wy) - tx_target, ty_target, tyaw_target, tc_target, csp_target = generate_target_course(targetx, targety) + ob_borders = np.array([borders_x, borders_y]) + + tx, ty, tyaw, tc, csp = frenet_optimal_trajectory.generate_target_course(wx, wy) + tx_target, ty_target, tyaw_target, tc_target, csp_target = frenet_optimal_trajectory.generate_target_course(targetx, targety) # initial state c_speed = 0.0 / 3.6 # current speed [m/s] c_d = 0.0 # current lateral position [m] c_d_d = 0.0 # current lateral speed [m/s] c_d_dd = 0.0 # current lateral acceleration [m/s] - s0 = 0. # current course position + s0 = 0.0 # current course position - c_speed_target = 10.0 / 3.6 # current speed [m/s] + c_speed_target = 0.0 / 3.6 # current speed [m/s] c_d_target = 0.0 # current lateral position [m] c_d_d_target = 0.0 # current lateral speed [m/s] c_d_dd_target = 0.0 # current lateral acceleration [m/s] @@ -490,24 +229,16 @@ def main(json_file): area = 30.0 # animation area length [m] - pred_time = 4.0 - for i in range(SIM_LOOP): - # start = time.time() - - path_target = frenet_optimal_planning_target(csp_target, s0_target, - c_speed_target, c_d_target, c_d_d_target, c_d_dd_target, pred_time) + path_target = frenet_optimal_planning(csp_target, s0_target, c_speed_target, c_d_target, c_d_d_target, c_d_dd_target, ob_borders, 0.0, 0.0) ob_targetx.append(path_target.x[1]) ob_targety.append(path_target.y[1]) ob_target = np.array([ob_targetx,ob_targety]) - - path = frenet_optimal_planning( - csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target, pred_time, \ - s0_target, c_speed_target) + path = frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob_target, s0_target, c_speed_target) del ob_targetx[-1] del ob_targety[-1] @@ -525,7 +256,7 @@ def main(json_file): c_speed_target = path_target.s_d[1] - if(path_target.s_d[1] >= 11.0): + if(path_target.s_d[1] >= 11.0): # just for simulation purpose c_speed_target = 10.0 if (np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0) and (np.hypot(path_target.x[1] - tx_target[-1], path_target.y[1] - ty_target[-1]) <= 1.0): @@ -537,7 +268,6 @@ def main(json_file): plt.plot(tx, ty) plt.plot(ob_target[0], ob_target[1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") - # plt.plot(path.x[1], path.y[1], "vc") circle = plt.Circle((path.x[1], path.y[1]), ROBOT_RADIUS, color='b', fill=False) plt.gcf().gca().add_artist(circle) plt.plot(path_target.x[1:], path_target.y[1:], "-ob") @@ -548,9 +278,6 @@ def main(json_file): plt.grid(True) plt.pause(0.0001) - # stop = time.time() - # duration = stop-start - # print(duration) print("Finish") if show_animation: # pragma: no cover From 54002c9ae60f6cb5cff26e67d98bd713d22ffa4b Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Tue, 29 Oct 2019 10:55:10 +0100 Subject: [PATCH 9/9] resolved lgtm alerts --- PathPlanning/FrenetOptimalTrajectory/path_planner.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/path_planner.py b/PathPlanning/FrenetOptimalTrajectory/path_planner.py index 10b96e3b55..e3b570d59c 100644 --- a/PathPlanning/FrenetOptimalTrajectory/path_planner.py +++ b/PathPlanning/FrenetOptimalTrajectory/path_planner.py @@ -15,8 +15,6 @@ import numpy as np import matplotlib.pyplot as plt import copy -import math -import cubic_spline_planner import racing_line import sys @@ -50,7 +48,7 @@ -def calc_frenet_paths_lv(c_speed, c_d, c_d_d, c_d_dd, s0, s0_target, c_speed_target): # Low velocities +def calc_frenet_paths_lv(c_speed, c_d, c_d_d, c_d_dd, s0): # Low velocities frenet_paths = [] @@ -155,7 +153,7 @@ def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob, s0_target, if(c_speed == 0.0): print("###############") print("Low Velocities") - fplist = calc_frenet_paths_lv(c_speed, c_d, c_d_d, c_d_dd, s0, 0.0, 0.0) + fplist = calc_frenet_paths_lv(c_speed, c_d, c_d_d, c_d_dd, s0) fplist = frenet_optimal_trajectory.calc_global_paths(fplist, csp) fplist = frenet_optimal_trajectory.check_paths(fplist, ob) else: