From c0fe133bb6d4534cc0c7992b6f937bc37cde2cbd Mon Sep 17 00:00:00 2001 From: nandantumu Date: Mon, 19 Jun 2023 14:48:32 -0400 Subject: [PATCH 01/32] Added tests --- ...ion_checks.py => collision_checks_test.py} | 21 ++-- gym/f110_gym/unittest/gym_api_test.py | 5 +- gym/f110_gym/unittest/legacy_scan_gen.py | 102 ------------------ ...t_test_camera.py => pyglet_camera_test.py} | 0 .../{scan_sim.py => scan_sim_test.py} | 34 +++--- 5 files changed, 33 insertions(+), 129 deletions(-) rename gym/f110_gym/unittest/{collision_checks.py => collision_checks_test.py} (95%) delete mode 100644 gym/f110_gym/unittest/legacy_scan_gen.py rename gym/f110_gym/unittest/{pyglet_test_camera.py => pyglet_camera_test.py} (100%) rename gym/f110_gym/unittest/{scan_sim.py => scan_sim_test.py} (95%) diff --git a/gym/f110_gym/unittest/collision_checks.py b/gym/f110_gym/unittest/collision_checks_test.py similarity index 95% rename from gym/f110_gym/unittest/collision_checks.py rename to gym/f110_gym/unittest/collision_checks_test.py index c5c86f0e..21a850a4 100644 --- a/gym/f110_gym/unittest/collision_checks.py +++ b/gym/f110_gym/unittest/collision_checks_test.py @@ -250,17 +250,18 @@ def setUp(self): self.length = 0.32 self.width = 0.22 - def test_get_vert(self): + def test_get_vert(self, debug=False): test_pose = np.array([2.3, 6.7, 0.8]) vertices = get_vertices(test_pose, self.length, self.width) rect = np.vstack((vertices, vertices[0,:])) - import matplotlib.pyplot as plt - plt.scatter(test_pose[0], test_pose[1], c='red') - plt.plot(rect[:, 0], rect[:, 1]) - plt.xlim([1, 4]) - plt.ylim([5, 8]) - plt.axes().set_aspect('equal') - plt.show() + if debug: + import matplotlib.pyplot as plt + plt.scatter(test_pose[0], test_pose[1], c='red') + plt.plot(rect[:, 0], rect[:, 1]) + plt.xlim([1, 4]) + plt.ylim([5, 8]) + plt.axes().set_aspect('equal') + plt.show() self.assertTrue(vertices.shape == (4, 2)) def test_get_vert_fps(self): @@ -271,7 +272,7 @@ def test_get_vert_fps(self): elapsed = time.time() - start fps = 1000/elapsed print('get vertices fps:', fps) - self.assertTrue(fps>500) + self.assertTrue(fps>120) def test_random_collision(self): # perturb the body by a small amount and make sure it all collides with the original body @@ -290,7 +291,7 @@ def test_fps(self): elapsed = time.time() - start fps = 1000/elapsed print('gjk fps:', fps) - self.assertTrue(fps>500) + self.assertTrue(fps>120) if __name__ == '__main__': unittest.main() \ No newline at end of file diff --git a/gym/f110_gym/unittest/gym_api_test.py b/gym/f110_gym/unittest/gym_api_test.py index 6d3eedc8..1df97258 100644 --- a/gym/f110_gym/unittest/gym_api_test.py +++ b/gym/f110_gym/unittest/gym_api_test.py @@ -23,4 +23,7 @@ def test_gymnasium_api(self): env = gym.make('f110_gym:f110-v0', map=conf.map_path, map_ext=conf.map_ext, num_agents=1, timestep=0.01, integrator=Integrator.Euler) - check_env(env.unwrapped) \ No newline at end of file + check_env(env.unwrapped) + +if __name__ == '__main__': + unittest.main() \ No newline at end of file diff --git a/gym/f110_gym/unittest/legacy_scan_gen.py b/gym/f110_gym/unittest/legacy_scan_gen.py deleted file mode 100644 index 045d50d7..00000000 --- a/gym/f110_gym/unittest/legacy_scan_gen.py +++ /dev/null @@ -1,102 +0,0 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - - -""" -Utility functions to generate sample scan data from legacy C++ backend -Author: Hongrui Zheng - -The script generates sample scan data for 3 different maps used in the unit tests. - -Map 1: Levine - -Map 2: Berlin - -Map 3: Skirkanich -""" - -import numpy as np -import gym -import matplotlib.pyplot as plt - -thetas = np.linspace(-2.35, 2.35, num=1080) - -# init -executable_dir = '../../../build/' -mass= 3.74 -l_r = 0.17145 -I_z = 0.04712 -mu = 0.523 -h_cg = 0.074 -cs_f = 4.718 -cs_r = 5.4562 - -# test poses -num_test = 10 -test_poses = np.zeros((num_test, 3)) -test_poses[:, 2] = np.linspace(-1., 1., num=num_test) - -# map 1: vegas -map_path = '../../../maps/vegas.yaml' -map_ext = '.png' -racecar_env = gym.make('f110_gym:f110-v0') -racecar_env.init_map(map_path, map_ext, False, False) -racecar_env.update_params(mu, h_cg, l_r, cs_f, cs_r, I_z, mass, executable_dir, double_finish=True) -vegas_scan = np.empty((num_test, 1080)) -for i in range(test_poses.shape[0]): - x = [test_poses[i, 0], 200.] - y = [test_poses[i, 1], 200.] - theta = [test_poses[i, 2], 0.] - obs,_,_,_ = racecar_env.reset({'x': x, 'y': y, 'theta': theta}) - vegas_scan[i,:] = obs['scans'][0] - -# map 2: berlin -map_path = '../../../maps/berlin.yaml' -map_ext = '.png' -racecar_env = gym.make('f110_gym:f110-v0') -racecar_env.init_map(map_path, map_ext, False, False) -racecar_env.update_params(mu, h_cg, l_r, cs_f, cs_r, I_z, mass, executable_dir, double_finish=True) -berlin_scan = np.empty((num_test, 1080)) -for i in range(test_poses.shape[0]): - x = [test_poses[i, 0], 200.] - y = [test_poses[i, 1], 200.] - theta = [test_poses[i, 2], 0.] - obs,_,_,_ = racecar_env.reset({'x': x, 'y': y, 'theta': theta}) - berlin_scan[i,:] = obs['scans'][0] - -# map 3: skirk -map_path = '../../../maps/skirk.yaml' -map_ext = '.png' -racecar_env = gym.make('f110_gym:f110-v0') -racecar_env.init_map(map_path, map_ext, False, False) -racecar_env.update_params(mu, h_cg, l_r, cs_f, cs_r, I_z, mass, executable_dir, double_finish=True) -skirk_scan = np.empty((num_test, 1080)) -for i in range(test_poses.shape[0]): - x = [test_poses[i, 0], 200.] - y = [test_poses[i, 1], 200.] - theta = [test_poses[i, 2], 0.] - obs,_,_,_ = racecar_env.reset({'x': x, 'y': y, 'theta': theta}) - skirk_scan[i,:] = obs['scans'][0] - -# package data -np.savez_compressed('legacy_scan.npz', vegas=vegas_scan, berlin=berlin_scan, skirk=skirk_scan) \ No newline at end of file diff --git a/gym/f110_gym/unittest/pyglet_test_camera.py b/gym/f110_gym/unittest/pyglet_camera_test.py similarity index 100% rename from gym/f110_gym/unittest/pyglet_test_camera.py rename to gym/f110_gym/unittest/pyglet_camera_test.py diff --git a/gym/f110_gym/unittest/scan_sim.py b/gym/f110_gym/unittest/scan_sim_test.py similarity index 95% rename from gym/f110_gym/unittest/scan_sim.py rename to gym/f110_gym/unittest/scan_sim_test.py index 7f203bfe..ed262f7d 100644 --- a/gym/f110_gym/unittest/scan_sim.py +++ b/gym/f110_gym/unittest/scan_sim_test.py @@ -318,7 +318,7 @@ def setUp(self): self.berlin_scan = sample_scan['berlin'] self.skirk_scan = sample_scan['skirk'] - def test_map_berlin(self): + def test_map_berlin(self, debug=False): scan_sim = ScanSimulator2D(self.num_beams, self.fov) new_berlin = np.empty((self.num_test, self.num_beams)) map_path = '../../../maps/berlin.yaml' @@ -332,16 +332,17 @@ def test_map_berlin(self): mse = np.mean(diff**2) # print('Levine distance test, norm: ' + str(norm)) - # plotting - import matplotlib.pyplot as plt - theta = np.linspace(-self.fov/2., self.fov/2., num=self.num_beams) - plt.polar(theta, new_berlin[1,:], '.', lw=0) - plt.polar(theta, self.berlin_scan[1,:], '.', lw=0) - plt.show() + if debug: + # plotting + import matplotlib.pyplot as plt + theta = np.linspace(-self.fov/2., self.fov/2., num=self.num_beams) + plt.polar(theta, new_berlin[1,:], '.', lw=0) + plt.polar(theta, self.berlin_scan[1,:], '.', lw=0) + plt.show() self.assertLess(mse, 2.) - def test_map_skirk(self): + def test_map_skirk(self, debug=False): scan_sim = ScanSimulator2D(self.num_beams, self.fov) new_skirk = np.empty((self.num_test, self.num_beams)) map_path = '../../../maps/skirk.yaml' @@ -356,12 +357,13 @@ def test_map_skirk(self): mse = np.mean(diff**2) print('skirk distance test, mse: ' + str(mse)) - # plotting - import matplotlib.pyplot as plt - theta = np.linspace(-self.fov/2., self.fov/2., num=self.num_beams) - plt.polar(theta, new_skirk[1,:], '.', lw=0) - plt.polar(theta, self.skirk_scan[1,:], '.', lw=0) - plt.show() + if debug: + # plotting + import matplotlib.pyplot as plt + theta = np.linspace(-self.fov/2., self.fov/2., num=self.num_beams) + plt.polar(theta, new_skirk[1,:], '.', lw=0) + plt.polar(theta, self.skirk_scan[1,:], '.', lw=0) + plt.show() self.assertLess(mse, 2.) @@ -426,5 +428,5 @@ def update(i): plt.show() if __name__ == '__main__': - # unittest.main() - main() \ No newline at end of file + unittest.main() + #main() \ No newline at end of file From 7095945e3e8e7ff2b57807a2b7433606b2b58e96 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Fri, 23 Jun 2023 19:29:27 -0400 Subject: [PATCH 02/32] Package architecture and setup fixes. --- .github/workflows/ci.yml | 27 ++- LICENSE | 1 + gym/f110_gym/envs/base_classes.py | 24 --- gym/f110_gym/envs/collision_models.py | 24 --- gym/f110_gym/envs/dynamic_models.py | 20 -- gym/f110_gym/envs/f110_env_backup.py | 22 --- gym/f110_gym/unittest/__init__.py | 1 - gym/f110_gym/unittest/pyglet_camera_test.py | 131 ------------- gym/f110_gym/unittest/pyglet_test.py | 180 ------------------ pytest.ini | 6 + setup.py | 3 +- tests/__init__.py | 0 .../collision_checks_test.py | 26 +-- .../unittest => tests}/dynamics_test.py | 16 +- .../unittest => tests}/gym_api_test.py | 2 +- .../unittest => tests}/legacy_scan.npz | Bin .../unittest => tests}/random_trackgen.py | 23 --- .../unittest => tests}/scan_sim_test.py | 26 +-- 18 files changed, 38 insertions(+), 494 deletions(-) delete mode 100644 gym/f110_gym/unittest/__init__.py delete mode 100644 gym/f110_gym/unittest/pyglet_camera_test.py delete mode 100644 gym/f110_gym/unittest/pyglet_test.py create mode 100644 pytest.ini create mode 100644 tests/__init__.py rename {gym/f110_gym/unittest => tests}/collision_checks_test.py (86%) rename {gym/f110_gym/unittest => tests}/dynamics_test.py (90%) rename {gym/f110_gym/unittest => tests}/gym_api_test.py (90%) rename {gym/f110_gym/unittest => tests}/legacy_scan.npz (100%) rename {gym/f110_gym/unittest => tests}/random_trackgen.py (85%) rename {gym/f110_gym/unittest => tests}/scan_sim_test.py (92%) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 4d5256ea..80a88021 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -2,9 +2,12 @@ name: CI on: push: - branches: [ main ] + branches: [ main , 'v*', 'dev_ci_testing'] pull_request: - branches: [ main ] + branches: [ main , 'v*' ] + +permissions: + contents: read jobs: build: @@ -13,7 +16,7 @@ jobs: strategy: fail-fast: false matrix: - python-version: ["3.8", "3.9"] + python-version: ["3.8", "3.9", "3.10", "3.11"] steps: - uses: actions/checkout@v2 @@ -23,7 +26,25 @@ jobs: with: python-version: ${{ matrix.python-version }} + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install flake8 pytest + if [ -f requirements.txt ]; then pip install -r requirements.txt; fi + - name: Install run: | python -m pip install --upgrade pip pip install -e . + + - name: Lint with flake8 + run: | + # stop the build if there are Python syntax errors or undefined names + flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics + # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide + flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + + - name: Test with pytest + run: | + pytest + diff --git a/LICENSE b/LICENSE index 1f905d6f..f83bea7e 100644 --- a/LICENSE +++ b/LICENSE @@ -1,6 +1,7 @@ MIT License Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng +Copyright (c) 2023 Hongrui Zheng, Renukanandan Tumu, Luigi Berducci, Ahmad Amine Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal diff --git a/gym/f110_gym/envs/base_classes.py b/gym/f110_gym/envs/base_classes.py index 192e32eb..d04a78ad 100644 --- a/gym/f110_gym/envs/base_classes.py +++ b/gym/f110_gym/envs/base_classes.py @@ -1,27 +1,3 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - - """ Prototype of base classes Replacement of the old RaceCar, Simulator classes in C++ diff --git a/gym/f110_gym/envs/collision_models.py b/gym/f110_gym/envs/collision_models.py index 45885e7c..3718a344 100644 --- a/gym/f110_gym/envs/collision_models.py +++ b/gym/f110_gym/envs/collision_models.py @@ -1,27 +1,3 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - - """ Prototype of Utility functions and GJK algorithm for Collision checks between vehicles Originally from https://github.com/kroitor/gjk.c diff --git a/gym/f110_gym/envs/dynamic_models.py b/gym/f110_gym/envs/dynamic_models.py index ec18e909..25518052 100644 --- a/gym/f110_gym/envs/dynamic_models.py +++ b/gym/f110_gym/envs/dynamic_models.py @@ -1,17 +1,3 @@ -# Copyright 2020 Technical University of Munich, Professorship of Cyber-Physical Systems, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - -# 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - -# 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - -# 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. - -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - - """ Prototype of vehicle dynamics functions and classes for simulating 2D Single Track dynamic model @@ -26,7 +12,6 @@ import unittest import time -@njit(cache=True) def accl_constraints(vel, accl, v_switch, a_max, v_min, v_max): """ Acceleration constraints, adjusts the acceleration based on constraints @@ -59,7 +44,6 @@ def accl_constraints(vel, accl, v_switch, a_max, v_min, v_max): return accl -@njit(cache=True) def steering_constraint(steering_angle, steering_velocity, s_min, s_max, sv_min, sv_max): """ Steering constraints, adjusts the steering velocity based on constraints @@ -86,8 +70,6 @@ def steering_constraint(steering_angle, steering_velocity, s_min, s_max, sv_min, return steering_velocity - -@njit(cache=True) def vehicle_dynamics_ks(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): """ Single Track Kinematic Vehicle Dynamics. @@ -120,7 +102,6 @@ def vehicle_dynamics_ks(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max x[3]/lwb*np.tan(x[2])]) return f -@njit(cache=True) def vehicle_dynamics_st(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): """ Single Track Dynamic Vehicle Dynamics. @@ -175,7 +156,6 @@ def vehicle_dynamics_st(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max return f -@njit(cache=True) def pid(speed, steer, current_speed, current_steer, max_sv, max_a, max_v, min_v): """ Basic controller for speed/steer -> accl./steer vel. diff --git a/gym/f110_gym/envs/f110_env_backup.py b/gym/f110_gym/envs/f110_env_backup.py index fa818b6f..5c2d7349 100644 --- a/gym/f110_gym/envs/f110_env_backup.py +++ b/gym/f110_gym/envs/f110_env_backup.py @@ -1,25 +1,3 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - ''' Author: Hongrui Zheng ''' diff --git a/gym/f110_gym/unittest/__init__.py b/gym/f110_gym/unittest/__init__.py deleted file mode 100644 index 53d19b7c..00000000 --- a/gym/f110_gym/unittest/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from gym.envs.unittest.scan_sim import * \ No newline at end of file diff --git a/gym/f110_gym/unittest/pyglet_camera_test.py b/gym/f110_gym/unittest/pyglet_camera_test.py deleted file mode 100644 index 46ba26a3..00000000 --- a/gym/f110_gym/unittest/pyglet_camera_test.py +++ /dev/null @@ -1,131 +0,0 @@ -import pyglet -from pyglet.gl import * - -# Zooming constants -ZOOM_IN_FACTOR = 1.2 -ZOOM_OUT_FACTOR = 1/ZOOM_IN_FACTOR - -class App(pyglet.window.Window): - - def __init__(self, width, height, *args, **kwargs): - conf = Config(sample_buffers=1, - samples=4, - depth_size=16, - double_buffer=True) - super().__init__(width, height, config=conf, *args, **kwargs) - - #Initialize camera values - self.left = 0 - self.right = width - self.bottom = 0 - self.top = height - self.zoom_level = 1 - self.zoomed_width = width - self.zoomed_height = height - - def init_gl(self, width, height): - # Set clear color - glClearColor(0/255, 0/255, 0/255, 0/255) - - # Set antialiasing - glEnable( GL_LINE_SMOOTH ) - glEnable( GL_POLYGON_SMOOTH ) - glHint( GL_LINE_SMOOTH_HINT, GL_NICEST ) - - # Set alpha blending - glEnable( GL_BLEND ) - glBlendFunc( GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA ) - - # Set viewport - glViewport( 0, 0, width, height ) - - def on_resize(self, width, height): - super().on_resize(width, height) - size = self.get_size() - self.left = 0 - self.right = size[0] - self.bottom = 0 - self.top = size[1] - self.zoomed_width = size[0] - self.zoomed_height = size[1] - - # # Set window values - # self.width = width - # self.height = height - # # Initialize OpenGL context - # self.init_gl(width, height) - # self.width = width - # self.height = height - # pass - - def on_mouse_drag(self, x, y, dx, dy, buttons, modifiers): - # Move camera - self.left -= dx*self.zoom_level - self.right -= dx*self.zoom_level - self.bottom -= dy*self.zoom_level - self.top -= dy*self.zoom_level - - def on_mouse_scroll(self, x, y, dx, dy): - # Get scale factor - f = ZOOM_IN_FACTOR if dy > 0 else ZOOM_OUT_FACTOR if dy < 0 else 1 - # If zoom_level is in the proper range - if .2 < self.zoom_level*f < 5: - - self.zoom_level *= f - - size = self.get_size() - - mouse_x = x/size[0] - mouse_y = y/size[1] - - mouse_x_in_world = self.left + mouse_x*self.zoomed_width - mouse_y_in_world = self.bottom + mouse_y*self.zoomed_height - - self.zoomed_width *= f - self.zoomed_height *= f - - self.left = mouse_x_in_world - mouse_x*self.zoomed_width - self.right = mouse_x_in_world + (1 - mouse_x)*self.zoomed_width - self.bottom = mouse_y_in_world - mouse_y*self.zoomed_height - self.top = mouse_y_in_world + (1 - mouse_y)*self.zoomed_height - - def on_draw(self): - # Initialize Projection matrix - glMatrixMode( GL_PROJECTION ) - glLoadIdentity() - - # Initialize Modelview matrix - glMatrixMode( GL_MODELVIEW ) - glLoadIdentity() - # Save the default modelview matrix - glPushMatrix() - - # Clear window with ClearColor - glClear( GL_COLOR_BUFFER_BIT ) - - # Set orthographic projection matrix - glOrtho( self.left, self.right, self.bottom, self.top, 1, -1 ) - - # Draw quad - glBegin( GL_QUADS ) - glColor3ub( 0xFF, 0, 0 ) - glVertex2i( 10, 10 ) - - glColor3ub( 0xFF, 0xFF, 0 ) - glVertex2i( 110, 10 ) - - glColor3ub( 0, 0xFF, 0 ) - glVertex2i( 110, 110 ) - - glColor3ub( 0, 0, 0xFF ) - glVertex2i( 10, 110 ) - glEnd() - - # Remove default modelview matrix - glPopMatrix() - - def run(self): - pyglet.app.run() - - -App(800, 800, resizable=True).run() \ No newline at end of file diff --git a/gym/f110_gym/unittest/pyglet_test.py b/gym/f110_gym/unittest/pyglet_test.py deleted file mode 100644 index 43449019..00000000 --- a/gym/f110_gym/unittest/pyglet_test.py +++ /dev/null @@ -1,180 +0,0 @@ -import numpy as np -from PIL import Image -import yaml - -from pyglet.gl import * -import pyglet -from pyglet import font, graphics, window - -import argparse - -class Camera: - """ A simple 2D camera that contains the speed and offset.""" - - def __init__(self, window: pyglet.window.Window, scroll_speed=1, min_zoom=1, max_zoom=4): - assert min_zoom <= max_zoom, "Minimum zoom must not be greater than maximum zoom" - self._window = window - self.scroll_speed = scroll_speed - self.max_zoom = max_zoom - self.min_zoom = min_zoom - self.offset_x = 0 - self.offset_y = 0 - self._zoom = max(min(1, self.max_zoom), self.min_zoom) - - @property - def zoom(self): - return self._zoom - - @zoom.setter - def zoom(self, value): - """ Here we set zoom, clamp value to minimum of min_zoom and max of max_zoom.""" - self._zoom = max(min(value, self.max_zoom), self.min_zoom) - - @property - def position(self): - """Query the current offset.""" - return self.offset_x, self.offset_y - - @position.setter - def position(self, value): - """Set the scroll offset directly.""" - self.offset_x, self.offset_y = value - - def move(self, axis_x, axis_y): - """ Move axis direction with scroll_speed. - Example: Move left -> move(-1, 0) - """ - self.offset_x += self.scroll_speed * axis_x - self.offset_y += self.scroll_speed * axis_y - - def begin(self): - # Set the current camera offset so you can draw your scene. - - # Translate using the offset. - view_matrix = self._window.view.translate(-self.offset_x * self._zoom, -self.offset_y * self._zoom, 0) - # Scale by zoom level. - view_matrix = view_matrix.scale(self._zoom, self._zoom, 1) - - self._window.view = view_matrix - - def end(self): - # Since this is a matrix, you will need to reverse the translate after rendering otherwise - # it will multiply the current offset every draw update pushing it further and further away. - - # Reverse scale, since that was the last transform. - view_matrix = self._window.view.scale(1 / self._zoom, 1 / self._zoom, 1) - # Reverse translate. - view_matrix = view_matrix.translate(self.offset_x * self._zoom, self.offset_y * self._zoom, 0) - - self._window.view = view_matrix - - def __enter__(self): - self.begin() - - def __exit__(self, exception_type, exception_value, traceback): - self.end() - - -class CenteredCamera(Camera): - """A simple 2D camera class. 0, 0 will be the center of the screen, as opposed to the bottom left.""" - - def begin(self): - x = -self._window.width // 2 / self._zoom + self.offset_x - y = -self._window.height // 2 / self._zoom + self.offset_y - - view_matrix = self._window.view.translate(-x * self._zoom, -y * self._zoom, 0) - view_matrix = view_matrix.scale(self._zoom, self._zoom, 1) - self._window.view = view_matrix - - def end(self): - x = -self._window.width // 2 / self._zoom + self.offset_x - y = -self._window.height // 2 / self._zoom + self.offset_y - - view_matrix = self._window.view.scale(1 / self._zoom, 1 / self._zoom, 1) - view_matrix = view_matrix.translate(x * self._zoom, y * self._zoom, 0) - self._window.view = view_matrix - - - -parser = argparse.ArgumentParser() -parser.add_argument('--map_path', type=str, required=True, help='Path to the map without extensions') -parser.add_argument('--map_ext', type=str, required=True, help='Extension of the map image file') -args = parser.parse_args() - -# load map yaml -with open(args.map_path + '.yaml', 'r') as yaml_stream: - try: - map_metada = yaml.safe_load(yaml_stream) - map_resolution = map_metada['resolution'] - origin = map_metada['origin'] - origin_x = origin[0] - origin_y = origin[1] - except yaml.YAMLError as ex: - print(ex) - -# load map image -map_img = np.array(Image.open(args.map_path + args.map_ext).transpose(Image.FLIP_TOP_BOTTOM)).astype(np.float64) -map_height = map_img.shape[0] -map_width = map_img.shape[1] - -# convert map pixels to coordinates -range_x = np.arange(map_width) -range_y = np.arange(map_height) -map_x, map_y = np.meshgrid(range_x, range_y) -map_x = (map_x * map_resolution + origin_x).flatten() -map_y = (map_y * map_resolution + origin_y).flatten() -map_z = np.zeros(map_y.shape) -map_coords = np.vstack((map_x, map_y, map_z)) - -# mask and only leave the obstacle points -map_mask = map_img == 0.0 -map_mask_flat = map_mask.flatten() -map_points = map_coords[:, map_mask_flat].T - -# prep opengl -try: - # Try and create a window with multisampling (antialiasing) - config = Config(sample_buffers=1, samples=4, - depth_size=16, double_buffer=True, ) - window = window.Window(resizable=True, config=config) -except window.NoSuchConfigException: - # Fall back to no multisampling for old hardware - window = window.Window(resizable=True) - -glClearColor(18/255, 4/255, 88/255, 1.) -glEnable(GL_DEPTH_TEST) -glTranslatef(25, -5, -60) - -cam = Camera(window) - -@window.event -def on_resize(width, height): - # Override the default on_resize handler to create a 3D projection - glViewport(0, 0, width, height) - glMatrixMode(GL_PROJECTION) - glLoadIdentity() - gluPerspective(60., width / float(height), .1, 1000.) - glMatrixMode(GL_MODELVIEW) - return pyglet.event.EVENT_HANDLED - -batch = graphics.Batch() - -points = [] -for i in range(map_points.shape[0]): - particle = batch.add(1, GL_POINTS, None, ('v3f/stream', [map_points[i, 0], map_points[i, 1], map_points[i, 2]])) - points.append(particle) - -def loop(dt): - print(pyglet.clock.get_fps()) - pass - -@window.event -def on_draw(): - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT) - glColor3f(254/255, 117/255, 254/255) - cam.begin() - batch.draw() - cam.end() - -pyglet.clock.schedule(loop) -pyglet.app.run() \ No newline at end of file diff --git a/pytest.ini b/pytest.ini new file mode 100644 index 00000000..c1a1c8d2 --- /dev/null +++ b/pytest.ini @@ -0,0 +1,6 @@ +[pytest] +minversion = 6.0 +addopts = -ra -q +testpaths = + tests + integration \ No newline at end of file diff --git a/setup.py b/setup.py index 054546fe..5d5d6e40 100644 --- a/setup.py +++ b/setup.py @@ -14,5 +14,6 @@ 'numba>=0.55.2', 'pyyaml>=5.3.1', 'pyglet<1.5', - 'pyopengl'] + 'pyopengl', + 'pytest'] ) diff --git a/tests/__init__.py b/tests/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/gym/f110_gym/unittest/collision_checks_test.py b/tests/collision_checks_test.py similarity index 86% rename from gym/f110_gym/unittest/collision_checks_test.py rename to tests/collision_checks_test.py index 21a850a4..d831db31 100644 --- a/gym/f110_gym/unittest/collision_checks_test.py +++ b/tests/collision_checks_test.py @@ -1,27 +1,3 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - - """ Prototype of Utility functions and GJK algorithm for Collision checks between vehicles Originally from https://github.com/kroitor/gjk.c @@ -31,6 +7,7 @@ import numpy as np from numba import njit + @njit(cache=True) def perpendicular(pt): """ @@ -238,6 +215,7 @@ def get_vertices(pose, length, width): import time import unittest + class CollisionTests(unittest.TestCase): def setUp(self): # test params diff --git a/gym/f110_gym/unittest/dynamics_test.py b/tests/dynamics_test.py similarity index 90% rename from gym/f110_gym/unittest/dynamics_test.py rename to tests/dynamics_test.py index 8eb16828..ae15a81b 100644 --- a/gym/f110_gym/unittest/dynamics_test.py +++ b/tests/dynamics_test.py @@ -1,17 +1,3 @@ -# Copyright 2020 Technical University of Munich, Professorship of Cyber-Physical Systems, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - -# 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - -# 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - -# 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. - -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - - """ Prototype of vehicle dynamics functions and classes for simulating 2D Single Track dynamic model @@ -204,7 +190,7 @@ def setUp(self): self.mu = 1.0489 self.C_Sf = 21.92/1.0489 self.C_Sr = 21.92/1.0489 - self.lf = 0.3048*3.793293 + self.lf = 0.3048*3.793293 self.lr = 0.3048*4.667707 self.h = 0.3048*2.01355 self.m = 4.4482216152605/0.3048*74.91452 diff --git a/gym/f110_gym/unittest/gym_api_test.py b/tests/gym_api_test.py similarity index 90% rename from gym/f110_gym/unittest/gym_api_test.py rename to tests/gym_api_test.py index 1df97258..940393b4 100644 --- a/gym/f110_gym/unittest/gym_api_test.py +++ b/tests/gym_api_test.py @@ -13,7 +13,7 @@ def test_gymnasium_api(self): from gymnasium.utils.env_checker import check_env import gymnasium as gym - example_dir = pathlib.Path(__file__).parent.parent.parent.parent / 'examples' + example_dir = pathlib.Path('examples') with open(example_dir / 'config_example_map.yaml') as file: conf_dict = yaml.load(file, Loader=yaml.FullLoader) diff --git a/gym/f110_gym/unittest/legacy_scan.npz b/tests/legacy_scan.npz similarity index 100% rename from gym/f110_gym/unittest/legacy_scan.npz rename to tests/legacy_scan.npz diff --git a/gym/f110_gym/unittest/random_trackgen.py b/tests/random_trackgen.py similarity index 85% rename from gym/f110_gym/unittest/random_trackgen.py rename to tests/random_trackgen.py index cb88e3f4..cc614480 100644 --- a/gym/f110_gym/unittest/random_trackgen.py +++ b/tests/random_trackgen.py @@ -1,26 +1,3 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - """ Generates random tracks. Adapted from https://gym.openai.com/envs/CarRacing-v0 diff --git a/gym/f110_gym/unittest/scan_sim_test.py b/tests/scan_sim_test.py similarity index 92% rename from gym/f110_gym/unittest/scan_sim_test.py rename to tests/scan_sim_test.py index ed262f7d..c8f96b60 100644 --- a/gym/f110_gym/unittest/scan_sim_test.py +++ b/tests/scan_sim_test.py @@ -1,27 +1,3 @@ -# MIT License - -# Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - - """ Prototype of Utility functions and classes for simulating 2D LIDAR scans Author: Hongrui Zheng @@ -314,7 +290,7 @@ def setUp(self): self.test_poses[:, 2] = np.linspace(-1., 1., num=self.num_test) # legacy gym data - sample_scan = np.load('legacy_scan.npz') + sample_scan = np.load('tests/legacy_scan.npz') self.berlin_scan = sample_scan['berlin'] self.skirk_scan = sample_scan['skirk'] From 461392c231320266423beefadff69dfb9692de68 Mon Sep 17 00:00:00 2001 From: Nandan Tumu <10603428+nandantumu@users.noreply.github.com> Date: Wed, 5 Jul 2023 16:51:39 -0700 Subject: [PATCH 03/32] Create lint.yml --- .github/workflows/lint.yml | 44 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) create mode 100644 .github/workflows/lint.yml diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml new file mode 100644 index 00000000..249b15d5 --- /dev/null +++ b/.github/workflows/lint.yml @@ -0,0 +1,44 @@ +name: CI + +on: + push: + branches: [ main , 'v*', 'dev_ci_testing'] + pull_request: + branches: [ main , 'v*' ] + +permissions: + contents: read + +jobs: + build: + + runs-on: ubuntu-latest + strategy: + fail-fast: false + matrix: + python-version: ["3.8", "3.9", "3.10", "3.11"] + + steps: + - uses: actions/checkout@v2 + + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python-version }} + + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install flake8 pytest + if [ -f requirements.txt ]; then pip install -r requirements.txt; fi + + - name: Install + run: | + python -m pip install --upgrade pip + pip install -e . + + - name: Lint with flake8 + run: | + # stop the build if there are Python syntax errors or undefined names + # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide + flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics From 5d77c85d1ddfeb166314e7b1273efef945d85ad3 Mon Sep 17 00:00:00 2001 From: Nandan Tumu <10603428+nandantumu@users.noreply.github.com> Date: Wed, 5 Jul 2023 16:51:54 -0700 Subject: [PATCH 04/32] Update ci.yml --- .github/workflows/ci.yml | 7 ------- 1 file changed, 7 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 80a88021..769b19b3 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -37,13 +37,6 @@ jobs: python -m pip install --upgrade pip pip install -e . - - name: Lint with flake8 - run: | - # stop the build if there are Python syntax errors or undefined names - flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics - # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide - flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - - name: Test with pytest run: | pytest From fd0cd71bf1e98da866ad193c4475d78872f5e334 Mon Sep 17 00:00:00 2001 From: Nandan Tumu <10603428+nandantumu@users.noreply.github.com> Date: Wed, 5 Jul 2023 16:53:10 -0700 Subject: [PATCH 05/32] Update lint.yml Changed workflow name --- .github/workflows/lint.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index 249b15d5..764bef30 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -1,4 +1,4 @@ -name: CI +name: Linting Checks on: push: From 075171f78cce2469c41bea790022834b9029412d Mon Sep 17 00:00:00 2001 From: Nandan Tumu Date: Wed, 5 Jul 2023 17:00:37 -0700 Subject: [PATCH 06/32] Updated workflows to run on dev branches, added Pipfiles --- .github/workflows/ci.yml | 2 +- .github/workflows/lint.yml | 2 +- Pipfile | 15 +++ Pipfile.lock | 201 +++++++++++++++++++++++++++++++++++++ 4 files changed, 218 insertions(+), 2 deletions(-) create mode 100644 Pipfile create mode 100644 Pipfile.lock diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 769b19b3..2e0fab90 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -2,7 +2,7 @@ name: CI on: push: - branches: [ main , 'v*', 'dev_ci_testing'] + branches: [ main , 'v*', 'dev*'] pull_request: branches: [ main , 'v*' ] diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index 764bef30..b2b91fca 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -2,7 +2,7 @@ name: Linting Checks on: push: - branches: [ main , 'v*', 'dev_ci_testing'] + branches: [ main , 'v*', 'dev_*'] pull_request: branches: [ main , 'v*' ] diff --git a/Pipfile b/Pipfile new file mode 100644 index 00000000..c277ffa1 --- /dev/null +++ b/Pipfile @@ -0,0 +1,15 @@ +[[source]] +url = "https://pypi.org/simple" +verify_ssl = true +name = "pypi" + +[packages] +numba = "*" +pillow = "*" +scipy = "*" + +[dev-packages] + +[requires] +python_version = "3.10" +python_full_version = "3.10.12" diff --git a/Pipfile.lock b/Pipfile.lock new file mode 100644 index 00000000..77720d4a --- /dev/null +++ b/Pipfile.lock @@ -0,0 +1,201 @@ +{ + "_meta": { + "hash": { + "sha256": "4393ee46a708fb9fcf6ff8647a0b295f7268f7330a3262c10c33b73b02ab14a5" + }, + "pipfile-spec": 6, + "requires": { + "python_full_version": "3.10.12", + "python_version": "3.10" + }, + "sources": [ + { + "name": "pypi", + "url": "https://pypi.org/simple", + "verify_ssl": true + } + ] + }, + "default": { + "llvmlite": { + "hashes": [ + "sha256:09f83ea7a54509c285f905d968184bba00fc31ebf12f2b6b1494d677bb7dde9b", + "sha256:0c23edd196bd797dc3a7860799054ea3488d2824ecabc03f9135110c2e39fcbc", + "sha256:3673c53cb21c65d2ff3704962b5958e967c6fc0bd0cff772998face199e8d87b", + "sha256:39a0b4d0088c01a469a5860d2e2d7a9b4e6a93c0f07eb26e71a9a872a8cadf8d", + "sha256:467b43836b388eaedc5a106d76761e388dbc4674b2f2237bc477c6895b15a634", + "sha256:4a7525db121f2e699809b539b5308228854ccab6693ecb01b52c44a2f5647e20", + "sha256:5b3076dc4e9c107d16dc15ecb7f2faf94f7736cd2d5e9f4dc06287fd672452c1", + "sha256:5cdb0d45df602099d833d50bd9e81353a5e036242d3c003c5b294fc61d1986b4", + "sha256:7b37297f3cbd68d14a97223a30620589d98ad1890e5040c9e5fc181063f4ed49", + "sha256:84747289775d0874e506f907a4513db889471607db19b04de97d144047fec885", + "sha256:84ce9b1c7a59936382ffde7871978cddcda14098e5a76d961e204523e5c372fb", + "sha256:9329b930d699699846623054121ed105fd0823ed2180906d3b3235d361645490", + "sha256:96707ebad8b051bbb4fc40c65ef93b7eeee16643bd4d579a14d11578e4b7a647", + "sha256:a36d9f244b6680cb90bbca66b146dabb2972f4180c64415c96f7c8a2d8b60a36", + "sha256:a66a5bd580951751b4268f4c3bddcef92682814d6bc72f3cd3bb67f335dd7097", + "sha256:bba2747cf5b4954e945c287fe310b3fcc484e2a9d1b0c273e99eb17d103bb0e6", + "sha256:bbd5e82cc990e5a3e343a3bf855c26fdfe3bfae55225f00efd01c05bbda79918", + "sha256:cda71de10a1f48416309e408ea83dab5bf36058f83e13b86a2961defed265568", + "sha256:e2dbbb8424037ca287983b115a29adf37d806baf7e1bf4a67bd2cffb74e085ed", + "sha256:e35766e42acef0fe7d1c43169a8ffc327a47808fae6a067b049fe0e9bbf84dd5", + "sha256:e44f854dc11559795bcdeaf12303759e56213d42dabbf91a5897aa2d8b033810", + "sha256:e74e7bec3235a1e1c9ad97d897a620c5007d0ed80c32c84c1d787e7daa17e4ec", + "sha256:f643d15aacd0b0b0dc8b74b693822ba3f9a53fa63bc6a178c2dba7cc88f42144", + "sha256:ff8f31111bb99d135ff296757dc81ab36c2dee54ed4bd429158a96da9807c316" + ], + "markers": "python_version >= '3.8'", + "version": "==0.40.1" + }, + "numba": { + "hashes": [ + "sha256:33c0500170d213e66d90558ad6aca57d3e03e97bb11da82e6d87ab793648cb17", + "sha256:3cf78d74ad9d289fbc1e5b1c9f2680fca7a788311eb620581893ab347ec37a7e", + "sha256:3d6483c27520d16cf5d122868b79cad79e48056ecb721b52d70c126bed65431e", + "sha256:4838edef2df5f056cb8974670f3d66562e751040c448eb0b67c7e2fec1726649", + "sha256:4c078f84b5529a7fdb8413bb33d5100f11ec7b44aa705857d9eb4e54a54ff505", + "sha256:53e9fab973d9e82c9f8449f75994a898daaaf821d84f06fbb0b9de2293dd9306", + "sha256:5a82bf37444039c732485c072fda21a361790ed990f88db57fd6941cd5e5d307", + "sha256:60ec56386076e9eed106a87c96626d5686fbb16293b9834f0849cf78c9491779", + "sha256:643cb09a9ba9e1bd8b060e910aeca455e9442361e80fce97690795ff9840e681", + "sha256:6c057ccedca95df23802b6ccad86bb318be624af45b5a38bb8412882be57a681", + "sha256:8e00ca63c5d0ad2beeb78d77f087b3a88c45ea9b97e7622ab2ec411a868420ee", + "sha256:93df62304ada9b351818ba19b1cfbddaf72cd89348e81474326ca0b23bf0bae1", + "sha256:9587ba1bf5f3035575e45562ada17737535c6d612df751e811d702693a72d95e", + "sha256:9a1b2b69448e510d672ff9a6b18d2db9355241d93c6a77677baa14bec67dc2a0", + "sha256:9b17fbe4a69dcd9a7cd49916b6463cd9a82af5f84911feeb40793b8bce00dfa7", + "sha256:9bcc36478773ce838f38afd9a4dfafc328d4ffb1915381353d657da7f6473282", + "sha256:a32ee263649aa3c3587b833d6311305379529570e6c20deb0c6f4fb5bc7020db", + "sha256:a3eac19529956185677acb7f01864919761bfffbb9ae04bbbe5e84bbc06cfc2b", + "sha256:ae50c8c90c2ce8057f9618b589223e13faa8cbc037d8f15b4aad95a2c33a0582", + "sha256:c0602e4f896e6a6d844517c3ab434bc978e7698a22a733cc8124465898c28fa8", + "sha256:db8268eb5093cae2288942a8cbd69c9352f6fe6e0bfa0a9a27679436f92e4248", + "sha256:e447c4634d1cc99ab50d4faa68f680f1d88b06a2a05acf134aa6fcc0342adeca", + "sha256:f47dd214adc5dcd040fe9ad2adbd2192133c9075d2189ce1b3d5f9d72863ef05", + "sha256:ff66d5b022af6c7d81ddbefa87768e78ed4f834ab2da6ca2fd0d60a9e69b94f5" + ], + "index": "pypi", + "version": "==0.57.1" + }, + "numpy": { + "hashes": [ + "sha256:04640dab83f7c6c85abf9cd729c5b65f1ebd0ccf9de90b270cd61935eef0197f", + "sha256:1452241c290f3e2a312c137a9999cdbf63f78864d63c79039bda65ee86943f61", + "sha256:222e40d0e2548690405b0b3c7b21d1169117391c2e82c378467ef9ab4c8f0da7", + "sha256:2541312fbf09977f3b3ad449c4e5f4bb55d0dbf79226d7724211acc905049400", + "sha256:31f13e25b4e304632a4619d0e0777662c2ffea99fcae2029556b17d8ff958aef", + "sha256:4602244f345453db537be5314d3983dbf5834a9701b7723ec28923e2889e0bb2", + "sha256:4979217d7de511a8d57f4b4b5b2b965f707768440c17cb70fbf254c4b225238d", + "sha256:4c21decb6ea94057331e111a5bed9a79d335658c27ce2adb580fb4d54f2ad9bc", + "sha256:6620c0acd41dbcb368610bb2f4d83145674040025e5536954782467100aa8835", + "sha256:692f2e0f55794943c5bfff12b3f56f99af76f902fc47487bdfe97856de51a706", + "sha256:7215847ce88a85ce39baf9e89070cb860c98fdddacbaa6c0da3ffb31b3350bd5", + "sha256:79fc682a374c4a8ed08b331bef9c5f582585d1048fa6d80bc6c35bc384eee9b4", + "sha256:7ffe43c74893dbf38c2b0a1f5428760a1a9c98285553c89e12d70a96a7f3a4d6", + "sha256:80f5e3a4e498641401868df4208b74581206afbee7cf7b8329daae82676d9463", + "sha256:95f7ac6540e95bc440ad77f56e520da5bf877f87dca58bd095288dce8940532a", + "sha256:9667575fb6d13c95f1b36aca12c5ee3356bf001b714fc354eb5465ce1609e62f", + "sha256:a5425b114831d1e77e4b5d812b69d11d962e104095a5b9c3b641a218abcc050e", + "sha256:b4bea75e47d9586d31e892a7401f76e909712a0fd510f58f5337bea9572c571e", + "sha256:b7b1fc9864d7d39e28f41d089bfd6353cb5f27ecd9905348c24187a768c79694", + "sha256:befe2bf740fd8373cf56149a5c23a0f601e82869598d41f8e188a0e9869926f8", + "sha256:c0bfb52d2169d58c1cdb8cc1f16989101639b34c7d3ce60ed70b19c63eba0b64", + "sha256:d11efb4dbecbdf22508d55e48d9c8384db795e1b7b51ea735289ff96613ff74d", + "sha256:dd80e219fd4c71fc3699fc1dadac5dcf4fd882bfc6f7ec53d30fa197b8ee22dc", + "sha256:e2926dac25b313635e4d6cf4dc4e51c8c0ebfed60b801c799ffc4c32bf3d1254", + "sha256:e98f220aa76ca2a977fe435f5b04d7b3470c0a2e6312907b37ba6068f26787f2", + "sha256:ed094d4f0c177b1b8e7aa9cba7d6ceed51c0e569a5318ac0ca9a090680a6a1b1", + "sha256:f136bab9c2cfd8da131132c2cf6cc27331dd6fae65f95f69dcd4ae3c3639c810", + "sha256:f3a86ed21e4f87050382c7bc96571755193c4c1392490744ac73d660e8f564a9" + ], + "markers": "python_version >= '3.8'", + "version": "==1.24.4" + }, + "pillow": { + "hashes": [ + "sha256:00e65f5e822decd501e374b0650146063fbb30a7264b4d2744bdd7b913e0cab5", + "sha256:040586f7d37b34547153fa383f7f9aed68b738992380ac911447bb78f2abe530", + "sha256:0b6eb5502f45a60a3f411c63187db83a3d3107887ad0d036c13ce836f8a36f1d", + "sha256:1f62406a884ae75fb2f818694469519fb685cc7eaff05d3451a9ebe55c646891", + "sha256:22c10cc517668d44b211717fd9775799ccec4124b9a7f7b3635fc5386e584992", + "sha256:3400aae60685b06bb96f99a21e1ada7bc7a413d5f49bce739828ecd9391bb8f7", + "sha256:349930d6e9c685c089284b013478d6f76e3a534e36ddfa912cde493f235372f3", + "sha256:368ab3dfb5f49e312231b6f27b8820c823652b7cd29cfbd34090565a015e99ba", + "sha256:38250a349b6b390ee6047a62c086d3817ac69022c127f8a5dc058c31ccef17f3", + "sha256:3a684105f7c32488f7153905a4e3015a3b6c7182e106fe3c37fbb5ef3e6994c3", + "sha256:3a82c40d706d9aa9734289740ce26460a11aeec2d9c79b7af87bb35f0073c12f", + "sha256:3b08d4cc24f471b2c8ca24ec060abf4bebc6b144cb89cba638c720546b1cf538", + "sha256:3ed64f9ca2f0a95411e88a4efbd7a29e5ce2cea36072c53dd9d26d9c76f753b3", + "sha256:3f07ea8d2f827d7d2a49ecf1639ec02d75ffd1b88dcc5b3a61bbb37a8759ad8d", + "sha256:520f2a520dc040512699f20fa1c363eed506e94248d71f85412b625026f6142c", + "sha256:5c6e3df6bdd396749bafd45314871b3d0af81ff935b2d188385e970052091017", + "sha256:608bfdee0d57cf297d32bcbb3c728dc1da0907519d1784962c5f0c68bb93e5a3", + "sha256:685ac03cc4ed5ebc15ad5c23bc555d68a87777586d970c2c3e216619a5476223", + "sha256:76de421f9c326da8f43d690110f0e79fe3ad1e54be811545d7d91898b4c8493e", + "sha256:76edb0a1fa2b4745fb0c99fb9fb98f8b180a1bbceb8be49b087e0b21867e77d3", + "sha256:7be600823e4c8631b74e4a0d38384c73f680e6105a7d3c6824fcf226c178c7e6", + "sha256:81ff539a12457809666fef6624684c008e00ff6bf455b4b89fd00a140eecd640", + "sha256:88af2003543cc40c80f6fca01411892ec52b11021b3dc22ec3bc9d5afd1c5334", + "sha256:8c11160913e3dd06c8ffdb5f233a4f254cb449f4dfc0f8f4549eda9e542c93d1", + "sha256:8f8182b523b2289f7c415f589118228d30ac8c355baa2f3194ced084dac2dbba", + "sha256:9211e7ad69d7c9401cfc0e23d49b69ca65ddd898976d660a2fa5904e3d7a9baa", + "sha256:92be919bbc9f7d09f7ae343c38f5bb21c973d2576c1d45600fce4b74bafa7ac0", + "sha256:9c82b5b3e043c7af0d95792d0d20ccf68f61a1fec6b3530e718b688422727396", + "sha256:9f7c16705f44e0504a3a2a14197c1f0b32a95731d251777dcb060aa83022cb2d", + "sha256:9fb218c8a12e51d7ead2a7c9e101a04982237d4855716af2e9499306728fb485", + "sha256:a74ba0c356aaa3bb8e3eb79606a87669e7ec6444be352870623025d75a14a2bf", + "sha256:b4f69b3700201b80bb82c3a97d5e9254084f6dd5fb5b16fc1a7b974260f89f43", + "sha256:c189af0545965fa8d3b9613cfdb0cd37f9d71349e0f7750e1fd704648d475ed2", + "sha256:c1fbe7621c167ecaa38ad29643d77a9ce7311583761abf7836e1510c580bf3dd", + "sha256:c7cf14a27b0d6adfaebb3ae4153f1e516df54e47e42dcc073d7b3d76111a8d86", + "sha256:c9f72a021fbb792ce98306ffb0c348b3c9cb967dce0f12a49aa4c3d3fdefa967", + "sha256:cd25d2a9d2b36fcb318882481367956d2cf91329f6892fe5d385c346c0649629", + "sha256:ce543ed15570eedbb85df19b0a1a7314a9c8141a36ce089c0a894adbfccb4568", + "sha256:ce7b031a6fc11365970e6a5686d7ba8c63e4c1cf1ea143811acbb524295eabed", + "sha256:d35e3c8d9b1268cbf5d3670285feb3528f6680420eafe35cccc686b73c1e330f", + "sha256:d50b6aec14bc737742ca96e85d6d0a5f9bfbded018264b3b70ff9d8c33485551", + "sha256:d5d0dae4cfd56969d23d94dc8e89fb6a217be461c69090768227beb8ed28c0a3", + "sha256:d5db32e2a6ccbb3d34d87c87b432959e0db29755727afb37290e10f6e8e62614", + "sha256:d72e2ecc68a942e8cf9739619b7f408cc7b272b279b56b2c83c6123fcfa5cdff", + "sha256:d737a602fbd82afd892ca746392401b634e278cb65d55c4b7a8f48e9ef8d008d", + "sha256:d80cf684b541685fccdd84c485b31ce73fc5c9b5d7523bf1394ce134a60c6883", + "sha256:db24668940f82321e746773a4bc617bfac06ec831e5c88b643f91f122a785684", + "sha256:dbc02381779d412145331789b40cc7b11fdf449e5d94f6bc0b080db0a56ea3f0", + "sha256:dffe31a7f47b603318c609f378ebcd57f1554a3a6a8effbc59c3c69f804296de", + "sha256:edf4392b77bdc81f36e92d3a07a5cd072f90253197f4a52a55a8cec48a12483b", + "sha256:efe8c0681042536e0d06c11f48cebe759707c9e9abf880ee213541c5b46c5bf3", + "sha256:f31f9fdbfecb042d046f9d91270a0ba28368a723302786c0009ee9b9f1f60199", + "sha256:f88a0b92277de8e3ca715a0d79d68dc82807457dae3ab8699c758f07c20b3c51", + "sha256:faaf07ea35355b01a35cb442dd950d8f1bb5b040a7787791a535de13db15ed90" + ], + "index": "pypi", + "version": "==10.0.0" + }, + "scipy": { + "hashes": [ + "sha256:08d957ca82d3535b3b9ba6c8ff355d78fe975271874e2af267cb5add5bd78625", + "sha256:249cfa465c379c9bb2c20123001e151ff5e29b351cbb7f9c91587260602c58d0", + "sha256:366a6a937110d80dca4f63b3f5b00cc89d36f678b2d124a01067b154e692bab1", + "sha256:39154437654260a52871dfde852adf1b93b1d1bc5dc0ffa70068f16ec0be2624", + "sha256:396fae3f8c12ad14c5f3eb40499fd06a6fef8393a6baa352a652ecd51e74e029", + "sha256:3b9963798df1d8a52db41a6fc0e6fa65b1c60e85d73da27ae8bb754de4792481", + "sha256:3e8eb42db36526b130dfbc417609498a6192381abc1975b91e3eb238e0b41c1a", + "sha256:512fdc18c65f76dadaca139348e525646d440220d8d05f6d21965b8d4466bccd", + "sha256:aec8c62fbe52914f9cf28d846cf0401dd80ab80788bbab909434eb336ed07c04", + "sha256:b41a0f322b4eb51b078cb3441e950ad661ede490c3aca66edef66f4b37ab1877", + "sha256:b4bb943010203465ac81efa392e4645265077b4d9e99b66cf3ed33ae12254173", + "sha256:b588311875c58d1acd4ef17c983b9f1ab5391755a47c3d70b6bd503a45bfaf71", + "sha256:ba94eeef3c9caa4cea7b402a35bb02a5714ee1ee77eb98aca1eed4543beb0f4c", + "sha256:be8c962a821957fdde8c4044efdab7a140c13294997a407eaee777acf63cbf0c", + "sha256:cce154372f0ebe88556ed06d7b196e9c2e0c13080ecb58d0f35062dc7cc28b47", + "sha256:d51565560565a0307ed06fa0ec4c6f21ff094947d4844d6068ed04400c72d0c3", + "sha256:e866514bc2d660608447b6ba95c8900d591f2865c07cca0aa4f7ff3c4ca70f30", + "sha256:fb5b492fa035334fd249f0973cc79ecad8b09c604b42a127a677b45a9a3d4289", + "sha256:ffb28e3fa31b9c376d0fb1f74c1f13911c8c154a760312fbee87a21eb21efe31" + ], + "index": "pypi", + "version": "==1.11.1" + } + }, + "develop": {} +} From 9e8c9c0642351b7972c80d5812f757b68ed416dd Mon Sep 17 00:00:00 2001 From: Nandan Tumu Date: Thu, 6 Jul 2023 14:37:16 -0700 Subject: [PATCH 07/32] Formatting changes to tests --- Pipfile | 2 + Pipfile.lock | 116 +++++- tests/collision_checks_test.py | 71 ++-- tests/dynamics_test.py | 657 ++++++++++++++++++++------------- tests/gym_api_test.py | 19 +- tests/random_trackgen.py | 140 +++---- tests/scan_sim_test.py | 202 ++++++---- 7 files changed, 764 insertions(+), 443 deletions(-) diff --git a/Pipfile b/Pipfile index c277ffa1..574c29c6 100644 --- a/Pipfile +++ b/Pipfile @@ -9,6 +9,8 @@ pillow = "*" scipy = "*" [dev-packages] +flake8 = "*" +black = "*" [requires] python_version = "3.10" diff --git a/Pipfile.lock b/Pipfile.lock index 77720d4a..31a9ceb8 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "4393ee46a708fb9fcf6ff8647a0b295f7268f7330a3262c10c33b73b02ab14a5" + "sha256": "d7937f644576260519209654eaa918509e1cda0420b9c530e59ea606a6c86a17" }, "pipfile-spec": 6, "requires": { @@ -197,5 +197,117 @@ "version": "==1.11.1" } }, - "develop": {} + "develop": { + "black": { + "hashes": [ + "sha256:064101748afa12ad2291c2b91c960be28b817c0c7eaa35bec09cc63aa56493c5", + "sha256:0945e13506be58bf7db93ee5853243eb368ace1c08a24c65ce108986eac65915", + "sha256:11c410f71b876f961d1de77b9699ad19f939094c3a677323f43d7a29855fe326", + "sha256:1c7b8d606e728a41ea1ccbd7264677e494e87cf630e399262ced92d4a8dac940", + "sha256:1d06691f1eb8de91cd1b322f21e3bfc9efe0c7ca1f0e1eb1db44ea367dff656b", + "sha256:3238f2aacf827d18d26db07524e44741233ae09a584273aa059066d644ca7b30", + "sha256:32daa9783106c28815d05b724238e30718f34155653d4d6e125dc7daec8e260c", + "sha256:35d1381d7a22cc5b2be2f72c7dfdae4072a3336060635718cc7e1ede24221d6c", + "sha256:3a150542a204124ed00683f0db1f5cf1c2aaaa9cc3495b7a3b5976fb136090ab", + "sha256:48f9d345675bb7fbc3dd85821b12487e1b9a75242028adad0333ce36ed2a6d27", + "sha256:50cb33cac881766a5cd9913e10ff75b1e8eb71babf4c7104f2e9c52da1fb7de2", + "sha256:562bd3a70495facf56814293149e51aa1be9931567474993c7942ff7d3533961", + "sha256:67de8d0c209eb5b330cce2469503de11bca4085880d62f1628bd9972cc3366b9", + "sha256:6b39abdfb402002b8a7d030ccc85cf5afff64ee90fa4c5aebc531e3ad0175ddb", + "sha256:6f3c333ea1dd6771b2d3777482429864f8e258899f6ff05826c3a4fcc5ce3f70", + "sha256:714290490c18fb0126baa0fca0a54ee795f7502b44177e1ce7624ba1c00f2331", + "sha256:7c3eb7cea23904399866c55826b31c1f55bbcd3890ce22ff70466b907b6775c2", + "sha256:92c543f6854c28a3c7f39f4d9b7694f9a6eb9d3c5e2ece488c327b6e7ea9b266", + "sha256:a6f6886c9869d4daae2d1715ce34a19bbc4b95006d20ed785ca00fa03cba312d", + "sha256:a8a968125d0a6a404842fa1bf0b349a568634f856aa08ffaff40ae0dfa52e7c6", + "sha256:c7ab5790333c448903c4b721b59c0d80b11fe5e9803d8703e84dcb8da56fec1b", + "sha256:e114420bf26b90d4b9daa597351337762b63039752bdf72bf361364c1aa05925", + "sha256:e198cf27888ad6f4ff331ca1c48ffc038848ea9f031a3b40ba36aced7e22f2c8", + "sha256:ec751418022185b0c1bb7d7736e6933d40bbb14c14a0abcf9123d1b159f98dd4", + "sha256:f0bd2f4a58d6666500542b26354978218a9babcdc972722f4bf90779524515f3" + ], + "index": "pypi", + "version": "==23.3.0" + }, + "click": { + "hashes": [ + "sha256:2739815aaa5d2c986a88f1e9230c55e17f0caad3d958a5e13ad0797c166db9e3", + "sha256:b97d0c74955da062a7d4ef92fadb583806a585b2ea81958a81bd72726cbb8e37" + ], + "markers": "python_version >= '3.7'", + "version": "==8.1.4" + }, + "flake8": { + "hashes": [ + "sha256:3833794e27ff64ea4e9cf5d410082a8b97ff1a06c16aa3d2027339cd0f1195c7", + "sha256:c61007e76655af75e6785a931f452915b371dc48f56efd765247c8fe68f2b181" + ], + "index": "pypi", + "version": "==6.0.0" + }, + "mccabe": { + "hashes": [ + "sha256:348e0240c33b60bbdf4e523192ef919f28cb2c3d7d5c7794f74009290f236325", + "sha256:6c2d30ab6be0e4a46919781807b4f0d834ebdd6c6e3dca0bda5a15f863427b6e" + ], + "markers": "python_version >= '3.6'", + "version": "==0.7.0" + }, + "mypy-extensions": { + "hashes": [ + "sha256:4392f6c0eb8a5668a69e23d168ffa70f0be9ccfd32b5cc2d26a34ae5b844552d", + "sha256:75dbf8955dc00442a438fc4d0666508a9a97b6bd41aa2f0ffe9d2f2725af0782" + ], + "markers": "python_version >= '3.5'", + "version": "==1.0.0" + }, + "packaging": { + "hashes": [ + "sha256:994793af429502c4ea2ebf6bf664629d07c1a9fe974af92966e4b8d2df7edc61", + "sha256:a392980d2b6cffa644431898be54b0045151319d1e7ec34f0cfed48767dd334f" + ], + "markers": "python_version >= '3.7'", + "version": "==23.1" + }, + "pathspec": { + "hashes": [ + "sha256:2798de800fa92780e33acca925945e9a19a133b715067cf165b8866c15a31687", + "sha256:d8af70af76652554bd134c22b3e8a1cc46ed7d91edcdd721ef1a0c51a84a5293" + ], + "markers": "python_version >= '3.7'", + "version": "==0.11.1" + }, + "platformdirs": { + "hashes": [ + "sha256:b0cabcb11063d21a0b261d557acb0a9d2126350e63b70cdf7db6347baea456dc", + "sha256:ca9ed98ce73076ba72e092b23d3c93ea6c4e186b3f1c3dad6edd98ff6ffcca2e" + ], + "markers": "python_version >= '3.7'", + "version": "==3.8.0" + }, + "pycodestyle": { + "hashes": [ + "sha256:347187bdb476329d98f695c213d7295a846d1152ff4fe9bacb8a9590b8ee7053", + "sha256:8a4eaf0d0495c7395bdab3589ac2db602797d76207242c17d470186815706610" + ], + "markers": "python_version >= '3.6'", + "version": "==2.10.0" + }, + "pyflakes": { + "hashes": [ + "sha256:ec55bf7fe21fff7f1ad2f7da62363d749e2a470500eab1b555334b67aa1ef8cf", + "sha256:ec8b276a6b60bd80defed25add7e439881c19e64850afd9b346283d4165fd0fd" + ], + "markers": "python_version >= '3.6'", + "version": "==3.0.1" + }, + "tomli": { + "hashes": [ + "sha256:939de3e7a6161af0c887ef91b7d41a53e7c5a1ca976325f429cb46ea9bc30ecc", + "sha256:de526c12914f0c550d15924c62d72abc48d6fe7364aa87328337a31007fe8a4f" + ], + "markers": "python_version < '3.11'", + "version": "==2.0.1" + } + } } diff --git a/tests/collision_checks_test.py b/tests/collision_checks_test.py index d831db31..9c12809b 100644 --- a/tests/collision_checks_test.py +++ b/tests/collision_checks_test.py @@ -21,7 +21,7 @@ def perpendicular(pt): """ temp = pt[0] pt[0] = pt[1] - pt[1] = -1*temp + pt[1] = -1 * temp return pt @@ -38,7 +38,7 @@ def tripleProduct(a, b, c): """ ac = a.dot(c) bc = b.dot(c) - return b*ac - a*bc + return b * ac - a * bc @njit(cache=True) @@ -52,7 +52,7 @@ def avgPoint(vertices): Returns: avg (np.ndarray, (2,)): average point of the vertices """ - return np.sum(vertices, axis=0)/vertices.shape[0] + return np.sum(vertices, axis=0) / vertices.shape[0] @njit(cache=True) @@ -130,7 +130,7 @@ def collision(vertices1, vertices2): if index < 2: b = simplex[0, :] - ab = b-a + ab = b - a d = tripleProduct(ab, ao, ab) if np.linalg.norm(d) < 1e-10: d = perpendicular(ab) @@ -138,8 +138,8 @@ def collision(vertices1, vertices2): b = simplex[1, :] c = simplex[0, :] - ab = b-a - ac = c-a + ab = b - a + ac = c - a acperp = tripleProduct(ab, ac, ac) @@ -158,10 +158,12 @@ def collision(vertices1, vertices2): iter_count += 1 return False + """ Utility functions for getting vertices by pose and shape """ + @njit(cache=True) def get_trmtx(pose): """ @@ -178,9 +180,10 @@ def get_trmtx(pose): th = pose[2] cos = np.cos(th) sin = np.sin(th) - H = np.array([[cos, -sin, 0., x], [sin, cos, 0., y], [0., 0., 1., 0.], [0., 0., 0., 1.]]) + H = np.array([[cos, -sin, 0.0, x], [sin, cos, 0.0, y], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]]) return H + @njit(cache=True) def get_vertices(pose, length, width): """ @@ -195,14 +198,14 @@ def get_vertices(pose, length, width): vertices (np.ndarray, (4, 2)): corner vertices of the vehicle body """ H = get_trmtx(pose) - rl = H.dot(np.asarray([[-length/2],[width/2],[0.], [1.]])).flatten() - rr = H.dot(np.asarray([[-length/2],[-width/2],[0.], [1.]])).flatten() - fl = H.dot(np.asarray([[length/2],[width/2],[0.], [1.]])).flatten() - fr = H.dot(np.asarray([[length/2],[-width/2],[0.], [1.]])).flatten() - rl = rl/rl[3] - rr = rr/rr[3] - fl = fl/fl[3] - fr = fr/fr[3] + rl = H.dot(np.asarray([[-length / 2], [width / 2], [0.0], [1.0]])).flatten() + rr = H.dot(np.asarray([[-length / 2], [-width / 2], [0.0], [1.0]])).flatten() + fl = H.dot(np.asarray([[length / 2], [width / 2], [0.0], [1.0]])).flatten() + fr = H.dot(np.asarray([[length / 2], [-width / 2], [0.0], [1.0]])).flatten() + rl = rl / rl[3] + rr = rr / rr[3] + fl = fl / fl[3] + fr = fr / fr[3] vertices = np.asarray([[rl[0], rl[1]], [rr[0], rr[1]], [fr[0], fr[1]], [fl[0], fl[1]]]) return vertices @@ -222,23 +225,24 @@ def setUp(self): np.random.seed(1234) # Collision check body - self.vertices1 = np.asarray([[4,11.],[5,5],[9,9],[10,10]]) + self.vertices1 = np.asarray([[4, 11.0], [5, 5], [9, 9], [10, 10]]) # car size self.length = 0.32 self.width = 0.22 - + def test_get_vert(self, debug=False): test_pose = np.array([2.3, 6.7, 0.8]) vertices = get_vertices(test_pose, self.length, self.width) - rect = np.vstack((vertices, vertices[0,:])) + rect = np.vstack((vertices, vertices[0, :])) if debug: import matplotlib.pyplot as plt - plt.scatter(test_pose[0], test_pose[1], c='red') + + plt.scatter(test_pose[0], test_pose[1], c="red") plt.plot(rect[:, 0], rect[:, 1]) plt.xlim([1, 4]) plt.ylim([5, 8]) - plt.axes().set_aspect('equal') + plt.axes().set_aspect("equal") plt.show() self.assertTrue(vertices.shape == (4, 2)) @@ -248,28 +252,29 @@ def test_get_vert_fps(self): for _ in range(1000): vertices = get_vertices(test_pose, self.length, self.width) elapsed = time.time() - start - fps = 1000/elapsed - print('get vertices fps:', fps) - self.assertTrue(fps>120) + fps = 1000 / elapsed + print("get vertices fps:", fps) + self.assertTrue(fps > 120) def test_random_collision(self): # perturb the body by a small amount and make sure it all collides with the original body for _ in range(1000): - a = self.vertices1 + np.random.normal(size=(self.vertices1.shape))/100. - b = self.vertices1 + np.random.normal(size=(self.vertices1.shape))/100. - self.assertTrue(collision(a,b)) + a = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 + b = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 + self.assertTrue(collision(a, b)) def test_fps(self): # also perturb the body but mainly want to test GJK speed start = time.time() for _ in range(1000): - a = self.vertices1 + np.random.normal(size=(self.vertices1.shape))/100. - b = self.vertices1 + np.random.normal(size=(self.vertices1.shape))/100. + a = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 + b = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 collision(a, b) elapsed = time.time() - start - fps = 1000/elapsed - print('gjk fps:', fps) - self.assertTrue(fps>120) + fps = 1000 / elapsed + print("gjk fps:", fps) + self.assertTrue(fps > 120) + -if __name__ == '__main__': - unittest.main() \ No newline at end of file +if __name__ == "__main__": + unittest.main() diff --git a/tests/dynamics_test.py b/tests/dynamics_test.py index ae15a81b..5224d509 100644 --- a/tests/dynamics_test.py +++ b/tests/dynamics_test.py @@ -5,233 +5,137 @@ Original implementation: https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ Author: Hongrui Zheng """ - +from f110_gym.envs.dynamic_models import func_KS, func_ST import numpy as np -from numba import njit - import unittest import time -@njit(cache=True) -def accl_constraints(vel, accl, v_switch, a_max, v_min, v_max): - """ - Acceleration constraints, adjusts the acceleration based on constraints - - Args: - vel (float): current velocity of the vehicle - accl (float): unconstraint desired acceleration - v_switch (float): switching velocity (velocity at which the acceleration is no longer able to create wheel spin) - a_max (float): maximum allowed acceleration - v_min (float): minimum allowed velocity - v_max (float): maximum allowed velocity - - Returns: - accl (float): adjusted acceleration - """ - - # positive accl limit - if vel > v_switch: - pos_limit = a_max*v_switch/vel - else: - pos_limit = a_max - - # accl limit reached? - if (vel <= v_min and accl <= 0) or (vel >= v_max and accl >= 0): - accl = 0. - elif accl <= -a_max: - accl = -a_max - elif accl >= pos_limit: - accl = pos_limit - - return accl - -@njit(cache=True) -def steering_constraint(steering_angle, steering_velocity, s_min, s_max, sv_min, sv_max): - """ - Steering constraints, adjusts the steering velocity based on constraints - - Args: - steering_angle (float): current steering_angle of the vehicle - steering_velocity (float): unconstraint desired steering_velocity - s_min (float): minimum steering angle - s_max (float): maximum steering angle - sv_min (float): minimum steering velocity - sv_max (float): maximum steering velocity - - Returns: - steering_velocity (float): adjusted steering velocity - """ - - # constraint steering velocity - if (steering_angle <= s_min and steering_velocity <= 0) or (steering_angle >= s_max and steering_velocity >= 0): - steering_velocity = 0. - elif steering_velocity <= sv_min: - steering_velocity = sv_min - elif steering_velocity >= sv_max: - steering_velocity = sv_max - - return steering_velocity - - -@njit(cache=True) -def vehicle_dynamics_ks(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): - """ - Single Track Kinematic Vehicle Dynamics. - - Args: - x (numpy.ndarray (3, )): vehicle state vector (x1, x2, x3, x4, x5) - x1: x position in global coordinates - x2: y position in global coordinates - x3: steering angle of front wheels - x4: velocity in x direction - x5: yaw angle - u (numpy.ndarray (2, )): control input vector (u1, u2) - u1: steering angle velocity of front wheels - u2: longitudinal acceleration - - Returns: - f (numpy.ndarray): right hand side of differential equations - """ - # wheelbase - lwb = lf + lr - - # constraints - u = np.array([steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max), accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max)]) - - # system dynamics - f = np.array([x[3]*np.cos(x[4]), - x[3]*np.sin(x[4]), - u[0], - u[1], - x[3]/lwb*np.tan(x[2])]) - return f - -@njit(cache=True) -def vehicle_dynamics_st(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): - """ - Single Track Dynamic Vehicle Dynamics. - - Args: - x (numpy.ndarray (3, )): vehicle state vector (x1, x2, x3, x4, x5, x6, x7) - x1: x position in global coordinates - x2: y position in global coordinates - x3: steering angle of front wheels - x4: velocity in x direction - x5: yaw angle - x6: yaw rate - x7: slip angle at vehicle center - u (numpy.ndarray (2, )): control input vector (u1, u2) - u1: steering angle velocity of front wheels - u2: longitudinal acceleration - - Returns: - f (numpy.ndarray): right hand side of differential equations - """ - - # gravity constant m/s^2 - g = 9.81 - - # constraints - u = np.array([steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max), accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max)]) - - # switch to kinematic model for small velocities - if abs(x[3]) < 0.1: - # wheelbase - lwb = lf + lr - - # system dynamics - x_ks = x[0:5] - f_ks = vehicle_dynamics_ks(x_ks, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max) - f = np.hstack((f_ks, np.array([u[1]/lwb*np.tan(x[2])+x[3]/(lwb*np.cos(x[2])**2)*u[0], - 0]))) - - else: - # system dynamics - f = np.array([x[3]*np.cos(x[6] + x[4]), - x[3]*np.sin(x[6] + x[4]), - u[0], - u[1], - x[5], - -mu*m/(x[3]*I*(lr+lf))*(lf**2*C_Sf*(g*lr-u[1]*h) + lr**2*C_Sr*(g*lf + u[1]*h))*x[5] \ - +mu*m/(I*(lr+lf))*(lr*C_Sr*(g*lf + u[1]*h) - lf*C_Sf*(g*lr - u[1]*h))*x[6] \ - +mu*m/(I*(lr+lf))*lf*C_Sf*(g*lr - u[1]*h)*x[2], - (mu/(x[3]**2*(lr+lf))*(C_Sr*(g*lf + u[1]*h)*lr - C_Sf*(g*lr - u[1]*h)*lf)-1)*x[5] \ - -mu/(x[3]*(lr+lf))*(C_Sr*(g*lf + u[1]*h) + C_Sf*(g*lr-u[1]*h))*x[6] \ - +mu/(x[3]*(lr+lf))*(C_Sf*(g*lr-u[1]*h))*x[2]]) - - return f - -@njit(cache=True) -def pid(speed, steer): - """ - Basic controller for speed/steer -> accl./steer vel. - - Args: - speed (float): desired input speed - steer (float): desired input steering angle - - Returns: - accl (float): desired input acceleration - sv (float): desired input steering velocity - """ - return - -def func_KS(x, t, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): - f = vehicle_dynamics_ks(x, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max) - return f - -def func_ST(x, t, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): - f = vehicle_dynamics_st(x, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max) - return f class DynamicsTest(unittest.TestCase): def setUp(self): # test params self.mu = 1.0489 - self.C_Sf = 21.92/1.0489 - self.C_Sr = 21.92/1.0489 - self.lf = 0.3048*3.793293 - self.lr = 0.3048*4.667707 - self.h = 0.3048*2.01355 - self.m = 4.4482216152605/0.3048*74.91452 - self.I = 4.4482216152605*0.3048*1321.416 - - #steering constraints - self.s_min = -1.066 #minimum steering angle [rad] - self.s_max = 1.066 #maximum steering angle [rad] - self.sv_min = -0.4 #minimum steering velocity [rad/s] - self.sv_max = 0.4 #maximum steering velocity [rad/s] - - #longitudinal constraints - self.v_min = -13.6 #minimum velocity [m/s] - self.v_max = 50.8 #minimum velocity [m/s] - self.v_switch = 7.319 #switching velocity [m/s] - self.a_max = 11.5 #maximum absolute acceleration [m/s^2] + self.C_Sf = 21.92 / 1.0489 + self.C_Sr = 21.92 / 1.0489 + self.lf = 0.3048 * 3.793293 + self.lr = 0.3048 * 4.667707 + self.h = 0.3048 * 2.01355 + self.m = 4.4482216152605 / 0.3048 * 74.91452 + self.I = 4.4482216152605 * 0.3048 * 1321.416 + + # steering constraints + self.s_min = -1.066 # minimum steering angle [rad] + self.s_max = 1.066 # maximum steering angle [rad] + self.sv_min = -0.4 # minimum steering velocity [rad/s] + self.sv_max = 0.4 # maximum steering velocity [rad/s] + + # longitudinal constraints + self.v_min = -13.6 # minimum velocity [m/s] + self.v_max = 50.8 # minimum velocity [m/s] + self.v_switch = 7.319 # switching velocity [m/s] + self.a_max = 11.5 # maximum absolute acceleration [m/s^2] def test_derivatives(self): # ground truth derivatives f_ks_gt = [16.3475935934250209, 0.4819314886013121, 0.1500000000000000, 5.1464424102339752, 0.2401426578627629] - f_st_gt = [15.7213512030862397, 0.0925527979719355, 0.1500000000000000, 5.3536773276413925, 0.0529001056654038, 0.6435589397748606, 0.0313297971641291] + f_st_gt = [ + 15.7213512030862397, + 0.0925527979719355, + 0.1500000000000000, + 5.3536773276413925, + 0.0529001056654038, + 0.6435589397748606, + 0.0313297971641291, + ] # system dynamics g = 9.81 - x_ks = np.array([3.9579422297936526, 0.0391650102771405, 0.0378491427211811, 16.3546957860883566, 0.0294717351052816]) - x_st = np.array([2.0233348142065677, 0.0041907137716636, 0.0197545248559617, 15.7216236334290116, 0.0025857914776859, 0.0529001056654038, 0.0033012170610298]) + x_ks = np.array( + [3.9579422297936526, 0.0391650102771405, 0.0378491427211811, 16.3546957860883566, 0.0294717351052816] + ) + x_st = np.array( + [ + 2.0233348142065677, + 0.0041907137716636, + 0.0197545248559617, + 15.7216236334290116, + 0.0025857914776859, + 0.0529001056654038, + 0.0033012170610298, + ] + ) v_delta = 0.15 - acc = 0.63*g - u = np.array([v_delta, acc]) - - f_ks = vehicle_dynamics_ks(x_ks, u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max) - f_st = vehicle_dynamics_st(x_st, u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max) + acc = 0.63 * g + u = np.array([v_delta, acc]) + + f_ks = vehicle_dynamics_ks( + x_ks, + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ) + f_st = vehicle_dynamics_st( + x_st, + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ) start = time.time() for i in range(10000): - f_st = vehicle_dynamics_st(x_st, u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max) + f_st = vehicle_dynamics_st( + x_st, + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ) duration = time.time() - start - avg_fps = 10000/duration + avg_fps = 10000 / duration - self.assertAlmostEqual(np.max(np.abs(f_ks_gt-f_ks)), 0.) - self.assertAlmostEqual(np.max(np.abs(f_st_gt-f_st)), 0.) + self.assertAlmostEqual(np.max(np.abs(f_ks_gt - f_ks)), 0.0) + self.assertAlmostEqual(np.max(np.abs(f_st_gt - f_st)), 0.0) self.assertGreater(avg_fps, 5000) def test_zeroinit_roll(self): @@ -239,15 +143,15 @@ def test_zeroinit_roll(self): # testing for zero initial state, zero input singularities g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] + t_start = 0.0 + t_final = 1.0 + delta0 = 0.0 + vel0 = 0.0 + Psi0 = 0.0 + dotPsi0 = 0.0 + beta0 = 0.0 + sy0 = 0.0 + initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] x0_KS = np.array(initial_state[0:5]) x0_ST = np.array(initial_state) @@ -256,30 +160,76 @@ def test_zeroinit_roll(self): t = np.arange(t_start, t_final, 1e-4) # set input: rolling car (velocity should stay constant) - u = np.array([0., 0.]) + u = np.array([0.0, 0.0]) # simulate single-track model - x_roll_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_roll_st = odeint( + func_ST, + x0_ST, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # simulate kinematic single-track model - x_roll_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - - self.assertTrue(all(x_roll_st[-1]==x0_ST)) - self.assertTrue(all(x_roll_ks[-1]==x0_KS)) + x_roll_ks = odeint( + func_KS, + x0_KS, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) + + self.assertTrue(all(x_roll_st[-1] == x0_ST)) + self.assertTrue(all(x_roll_ks[-1] == x0_KS)) def test_zeroinit_dec(self): from scipy.integrate import odeint # testing for zero initial state, decelerating input singularities g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] + t_start = 0.0 + t_final = 1.0 + delta0 = 0.0 + vel0 = 0.0 + Psi0 = 0.0 + dotPsi0 = 0.0 + beta0 = 0.0 + sy0 = 0.0 + initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] x0_KS = np.array(initial_state[0:5]) x0_ST = np.array(initial_state) @@ -288,17 +238,77 @@ def test_zeroinit_dec(self): t = np.arange(t_start, t_final, 1e-4) # set decel input - u = np.array([0., -0.7*g]) + u = np.array([0.0, -0.7 * g]) # simulate single-track model - x_dec_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_dec_st = odeint( + func_ST, + x0_ST, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # simulate kinematic single-track model - x_dec_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_dec_ks = odeint( + func_KS, + x0_KS, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # ground truth for single-track model - x_dec_st_gt = [-3.4335000000000013, 0.0000000000000000, 0.0000000000000000, -6.8670000000000018, 0.0000000000000000, 0.0000000000000000, 0.0000000000000000] + x_dec_st_gt = [ + -3.4335000000000013, + 0.0000000000000000, + 0.0000000000000000, + -6.8670000000000018, + 0.0000000000000000, + 0.0000000000000000, + 0.0000000000000000, + ] # ground truth for kinematic single-track model - x_dec_ks_gt = [-3.4335000000000013, 0.0000000000000000, 0.0000000000000000, -6.8670000000000018, 0.0000000000000000] + x_dec_ks_gt = [ + -3.4335000000000013, + 0.0000000000000000, + 0.0000000000000000, + -6.8670000000000018, + 0.0000000000000000, + ] self.assertTrue(all(abs(x_dec_st[-1] - x_dec_st_gt) < 1e-2)) self.assertTrue(all(abs(x_dec_ks[-1] - x_dec_ks_gt) < 1e-2)) @@ -309,15 +319,15 @@ def test_zeroinit_acc(self): # testing for zero initial state, accelerating with left steer input singularities # wheel spin and velocity should increase more wheel spin at rear g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] + t_start = 0.0 + t_final = 1.0 + delta0 = 0.0 + vel0 = 0.0 + Psi0 = 0.0 + dotPsi0 = 0.0 + beta0 = 0.0 + sy0 = 0.0 + initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] x0_KS = np.array(initial_state[0:5]) x0_ST = np.array(initial_state) @@ -326,17 +336,77 @@ def test_zeroinit_acc(self): t = np.arange(t_start, t_final, 1e-4) # set decel input - u = np.array([0.15, 0.63*g]) + u = np.array([0.15, 0.63 * g]) # simulate single-track model - x_acc_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_acc_st = odeint( + func_ST, + x0_ST, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # simulate kinematic single-track model - x_acc_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_acc_ks = odeint( + func_KS, + x0_KS, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # ground truth for single-track model - x_acc_st_gt = [3.0731976046859715, 0.2869835398304389, 0.1500000000000000, 6.1802999999999999, 0.1097747074946325, 0.3248268063223301, 0.0697547542798040] + x_acc_st_gt = [ + 3.0731976046859715, + 0.2869835398304389, + 0.1500000000000000, + 6.1802999999999999, + 0.1097747074946325, + 0.3248268063223301, + 0.0697547542798040, + ] # ground truth for kinematic single-track model - x_acc_ks_gt = [3.0845676868494927, 0.1484249221523042, 0.1500000000000000, 6.1803000000000017, 0.1203664469224163] + x_acc_ks_gt = [ + 3.0845676868494927, + 0.1484249221523042, + 0.1500000000000000, + 6.1803000000000017, + 0.1203664469224163, + ] self.assertTrue(all(abs(x_acc_st[-1] - x_acc_st_gt) < 1e-2)) self.assertTrue(all(abs(x_acc_ks[-1] - x_acc_ks_gt) < 1e-2)) @@ -346,15 +416,15 @@ def test_zeroinit_rollleft(self): # testing for zero initial state, rolling and steering left input singularities g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] + t_start = 0.0 + t_final = 1.0 + delta0 = 0.0 + vel0 = 0.0 + Psi0 = 0.0 + dotPsi0 = 0.0 + beta0 = 0.0 + sy0 = 0.0 + initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] x0_KS = np.array(initial_state[0:5]) x0_ST = np.array(initial_state) @@ -363,20 +433,77 @@ def test_zeroinit_rollleft(self): t = np.arange(t_start, t_final, 1e-4) # set decel input - u = np.array([0.15, 0.]) + u = np.array([0.15, 0.0]) # simulate single-track model - x_left_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_left_st = odeint( + func_ST, + x0_ST, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # simulate kinematic single-track model - x_left_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) + x_left_ks = odeint( + func_KS, + x0_KS, + t, + args=( + u, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, + ), + ) # ground truth for single-track model - x_left_st_gt = [0.0000000000000000, 0.0000000000000000, 0.1500000000000000, 0.0000000000000000, 0.0000000000000000, 0.0000000000000000, 0.0000000000000000] + x_left_st_gt = [ + 0.0000000000000000, + 0.0000000000000000, + 0.1500000000000000, + 0.0000000000000000, + 0.0000000000000000, + 0.0000000000000000, + 0.0000000000000000, + ] # ground truth for kinematic single-track model - x_left_ks_gt = [0.0000000000000000, 0.0000000000000000, 0.1500000000000000, 0.0000000000000000, 0.0000000000000000] + x_left_ks_gt = [ + 0.0000000000000000, + 0.0000000000000000, + 0.1500000000000000, + 0.0000000000000000, + 0.0000000000000000, + ] self.assertTrue(all(abs(x_left_st[-1] - x_left_st_gt) < 1e-2)) self.assertTrue(all(abs(x_left_ks[-1] - x_left_ks_gt) < 1e-2)) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tests/gym_api_test.py b/tests/gym_api_test.py index 940393b4..6bf5a292 100644 --- a/tests/gym_api_test.py +++ b/tests/gym_api_test.py @@ -13,17 +13,24 @@ def test_gymnasium_api(self): from gymnasium.utils.env_checker import check_env import gymnasium as gym - example_dir = pathlib.Path('examples') + example_dir = pathlib.Path("examples") - with open(example_dir / 'config_example_map.yaml') as file: + with open(example_dir / "config_example_map.yaml") as file: conf_dict = yaml.load(file, Loader=yaml.FullLoader) conf = Namespace(**conf_dict) conf.map_path = str(example_dir / conf.map_path) - env = gym.make('f110_gym:f110-v0', map=conf.map_path, map_ext=conf.map_ext, num_agents=1, timestep=0.01, - integrator=Integrator.Euler) + env = gym.make( + "f110_gym:f110-v0", + map=conf.map_path, + map_ext=conf.map_ext, + num_agents=1, + timestep=0.01, + integrator=Integrator.Euler, + ) check_env(env.unwrapped) -if __name__ == '__main__': - unittest.main() \ No newline at end of file + +if __name__ == "__main__": + unittest.main() diff --git a/tests/random_trackgen.py b/tests/random_trackgen.py index cc614480..38bd3cc4 100644 --- a/tests/random_trackgen.py +++ b/tests/random_trackgen.py @@ -15,47 +15,49 @@ import argparse parser = argparse.ArgumentParser() -parser.add_argument('--seed', type=int, default=123, help='Seed for the numpy rng.') -parser.add_argument('--num_maps', type=int, default=1, help='Number of maps to generate.') +parser.add_argument("--seed", type=int, default=123, help="Seed for the numpy rng.") +parser.add_argument("--num_maps", type=int, default=1, help="Number of maps to generate.") args = parser.parse_args() np.random.seed(args.seed) -if not os.path.exists('maps'): - print('Creating maps/ directory.') - os.makedirs('maps') -if not os.path.exists('centerline'): - print('Creating centerline/ directory.') - os.makedirs('centerline') +if not os.path.exists("maps"): + print("Creating maps/ directory.") + os.makedirs("maps") +if not os.path.exists("centerline"): + print("Creating centerline/ directory.") + os.makedirs("centerline") NUM_MAPS = args.num_maps WIDTH = 10.0 + + def create_track(): CHECKPOINTS = 16 SCALE = 6.0 - TRACK_RAD = 900/SCALE - TRACK_DETAIL_STEP = 21/SCALE + TRACK_RAD = 900 / SCALE + TRACK_DETAIL_STEP = 21 / SCALE TRACK_TURN_RATE = 0.31 - start_alpha = 0. + start_alpha = 0.0 # Create checkpoints checkpoints = [] for c in range(CHECKPOINTS): - alpha = 2*math.pi*c/CHECKPOINTS + np.random.uniform(0, 2*math.pi*1/CHECKPOINTS) - rad = np.random.uniform(TRACK_RAD/3, TRACK_RAD) - if c==0: + alpha = 2 * math.pi * c / CHECKPOINTS + np.random.uniform(0, 2 * math.pi * 1 / CHECKPOINTS) + rad = np.random.uniform(TRACK_RAD / 3, TRACK_RAD) + if c == 0: alpha = 0 - rad = 1.5*TRACK_RAD - if c==CHECKPOINTS-1: - alpha = 2*math.pi*c/CHECKPOINTS - start_alpha = 2*math.pi*(-0.5)/CHECKPOINTS - rad = 1.5*TRACK_RAD - checkpoints.append( (alpha, rad*math.cos(alpha), rad*math.sin(alpha)) ) + rad = 1.5 * TRACK_RAD + if c == CHECKPOINTS - 1: + alpha = 2 * math.pi * c / CHECKPOINTS + start_alpha = 2 * math.pi * (-0.5) / CHECKPOINTS + rad = 1.5 * TRACK_RAD + checkpoints.append((alpha, rad * math.cos(alpha), rad * math.sin(alpha))) road = [] # Go from one checkpoint to another to create track - x, y, beta = 1.5*TRACK_RAD, 0, 0 + x, y, beta = 1.5 * TRACK_RAD, 0, 0 dest_i = 0 laps = 0 track = [] @@ -68,7 +70,7 @@ def create_track(): visited_other_side = False if alpha < 0: visited_other_side = True - alpha += 2*math.pi + alpha += 2 * math.pi while True: failed = True while True: @@ -81,7 +83,7 @@ def create_track(): break if not failed: break - alpha -= 2*math.pi + alpha -= 2 * math.pi continue r1x = math.cos(beta) r1y = math.sin(beta) @@ -89,52 +91,52 @@ def create_track(): p1y = r1x dest_dx = dest_x - x dest_dy = dest_y - y - proj = r1x*dest_dx + r1y*dest_dy - while beta - alpha > 1.5*math.pi: - beta -= 2*math.pi - while beta - alpha < -1.5*math.pi: - beta += 2*math.pi + proj = r1x * dest_dx + r1y * dest_dy + while beta - alpha > 1.5 * math.pi: + beta -= 2 * math.pi + while beta - alpha < -1.5 * math.pi: + beta += 2 * math.pi prev_beta = beta proj *= SCALE - if proj > 0.3: - beta -= min(TRACK_TURN_RATE, abs(0.001*proj)) + if proj > 0.3: + beta -= min(TRACK_TURN_RATE, abs(0.001 * proj)) if proj < -0.3: - beta += min(TRACK_TURN_RATE, abs(0.001*proj)) - x += p1x*TRACK_DETAIL_STEP - y += p1y*TRACK_DETAIL_STEP - track.append( (alpha,prev_beta*0.5 + beta*0.5,x,y) ) + beta += min(TRACK_TURN_RATE, abs(0.001 * proj)) + x += p1x * TRACK_DETAIL_STEP + y += p1y * TRACK_DETAIL_STEP + track.append((alpha, prev_beta * 0.5 + beta * 0.5, x, y)) if laps > 4: - break + break no_freeze -= 1 - if no_freeze==0: - break + if no_freeze == 0: + break # Find closed loop i1, i2 = -1, -1 i = len(track) while True: i -= 1 - if i==0: + if i == 0: return False - pass_through_start = track[i][0] > start_alpha and track[i-1][0] <= start_alpha - if pass_through_start and i2==-1: + pass_through_start = track[i][0] > start_alpha and track[i - 1][0] <= start_alpha + if pass_through_start and i2 == -1: i2 = i - elif pass_through_start and i1==-1: + elif pass_through_start and i1 == -1: i1 = i break - print("Track generation: %i..%i -> %i-tiles track" % (i1, i2, i2-i1)) - assert i1!=-1 - assert i2!=-1 + print("Track generation: %i..%i -> %i-tiles track" % (i1, i2, i2 - i1)) + assert i1 != -1 + assert i2 != -1 - track = track[i1:i2-1] + track = track[i1 : i2 - 1] first_beta = track[0][1] first_perp_x = math.cos(first_beta) first_perp_y = math.sin(first_beta) # Length of perpendicular jump to put together head and tail well_glued_together = np.sqrt( - np.square( first_perp_x*(track[0][2] - track[-1][2]) ) + - np.square( first_perp_y*(track[0][3] - track[-1][3]) )) + np.square(first_perp_x * (track[0][2] - track[-1][2])) + np.square(first_perp_y * (track[0][3] - track[-1][3])) + ) if well_glued_together > TRACK_DETAIL_STEP: return False @@ -150,21 +152,20 @@ def create_track(): def convert_track(track, track_int, track_ext, iter): - # converts track to image and saves the centerline as waypoints fig, ax = plt.subplots() fig.set_size_inches(20, 20) - ax.plot(*track_int.T, color='black', linewidth=3) - ax.plot(*track_ext.T, color='black', linewidth=3) + ax.plot(*track_int.T, color="black", linewidth=3) + ax.plot(*track_ext.T, color="black", linewidth=3) plt.tight_layout() - ax.set_aspect('equal') + ax.set_aspect("equal") ax.set_xlim(-180, 300) ax.set_ylim(-300, 300) - plt.axis('off') - plt.savefig('maps/map' + str(iter) + '.png', dpi=80) + plt.axis("off") + plt.savefig("maps/map" + str(iter) + ".png", dpi=80) map_width, map_height = fig.canvas.get_width_height() - print('map size: ', map_width, map_height) + print("map size: ", map_width, map_height) # transform the track center line into pixel coordinates xy_pixels = ax.transData.transform(track) @@ -173,39 +174,38 @@ def convert_track(track, track_int, track_ext, iter): xy_pixels = xy_pixels - np.array([[origin_x_pix, origin_y_pix]]) - map_origin_x = -origin_x_pix*0.05 - map_origin_y = -origin_y_pix*0.05 + map_origin_x = -origin_x_pix * 0.05 + map_origin_y = -origin_y_pix * 0.05 # convert image using cv2 - cv_img = cv2.imread('maps/map' + str(iter) + '.png', -1) + cv_img = cv2.imread("maps/map" + str(iter) + ".png", -1) # convert to bw cv_img_bw = cv2.cvtColor(cv_img, cv2.COLOR_BGR2GRAY) # saving to img - cv2.imwrite('maps/map' + str(iter) + '.png', cv_img_bw) - cv2.imwrite('maps/map' + str(iter) + '.pgm', cv_img_bw) + cv2.imwrite("maps/map" + str(iter) + ".png", cv_img_bw) + cv2.imwrite("maps/map" + str(iter) + ".pgm", cv_img_bw) # create yaml file - yaml = open('maps/map' + str(iter) + '.yaml', 'w') - yaml.write('image: map' + str(iter) + '.pgm\n') - yaml.write('resolution: 0.062500\n') - yaml.write('origin: [' + str(map_origin_x) + ',' + str(map_origin_y) + ', 0.000000]\n') - yaml.write('negate: 0\noccupied_thresh: 0.45\nfree_thresh: 0.196') + yaml = open("maps/map" + str(iter) + ".yaml", "w") + yaml.write("image: map" + str(iter) + ".pgm\n") + yaml.write("resolution: 0.062500\n") + yaml.write("origin: [" + str(map_origin_x) + "," + str(map_origin_y) + ", 0.000000]\n") + yaml.write("negate: 0\noccupied_thresh: 0.45\nfree_thresh: 0.196") yaml.close() plt.close() # saving track centerline as a csv in ros coords - waypoints_csv = open('centerline/map' + str(iter) + '.csv', 'w') + waypoints_csv = open("centerline/map" + str(iter) + ".csv", "w") for row in xy_pixels: - waypoints_csv.write(str(0.05*row[0]) + ', ' + str(0.05*row[1]) + '\n') + waypoints_csv.write(str(0.05 * row[0]) + ", " + str(0.05 * row[1]) + "\n") waypoints_csv.close() - -if __name__ == '__main__': +if __name__ == "__main__": for i in range(NUM_MAPS): try: track, track_int, track_ext = create_track() except: - print('Random generator failed, retrying') + print("Random generator failed, retrying") continue - convert_track(track, track_int, track_ext, i) \ No newline at end of file + convert_track(track, track_int, track_ext, i) diff --git a/tests/scan_sim_test.py b/tests/scan_sim_test.py index c8f96b60..09f7b67b 100644 --- a/tests/scan_sim_test.py +++ b/tests/scan_sim_test.py @@ -13,6 +13,7 @@ import unittest import timeit + def get_dt(bitmap, resolution): """ Distance transformation, returns the distance matrix from the input bitmap. @@ -28,6 +29,7 @@ def get_dt(bitmap, resolution): dt = resolution * edt(bitmap) return dt + @njit(cache=True) def xy_2_rc(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution): """ @@ -38,7 +40,7 @@ def xy_2_rc(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution): y (float): coordinate in y (m) orig_x (float): x coordinate of the map origin (m) orig_y (float): y coordinate of the map origin (m) - + Returns: r (int): row number in the transform matrix of the given point c (int): column number in the transform matrix of the given point @@ -56,11 +58,12 @@ def xy_2_rc(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution): c = -1 r = -1 else: - c = int(x_rot/resolution) - r = int(y_rot/resolution) + c = int(x_rot / resolution) + r = int(y_rot / resolution) return r, c + @njit(cache=True) def distance_transform(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt): """ @@ -79,8 +82,11 @@ def distance_transform(x, y, orig_x, orig_y, orig_c, orig_s, height, width, reso distance = dt[r, c] return distance + @njit(cache=True) -def trace_ray(x, y, theta_index, sines, cosines, eps, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt, max_range): +def trace_ray( + x, y, theta_index, sines, cosines, eps, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt, max_range +): """ Find the length of a specific ray at a specific scan angle theta Purely math calculation and loops, should be JITted. @@ -95,7 +101,7 @@ def trace_ray(x, y, theta_index, sines, cosines, eps, orig_x, orig_y, orig_c, or Returns: total_distance (float): the distance to first obstacle on the current scan beam """ - + # int casting, and index precal trigs theta_index_ = int(theta_index) s = sines[theta_index_] @@ -115,11 +121,30 @@ def trace_ray(x, y, theta_index, sines, cosines, eps, orig_x, orig_y, orig_c, or # also keeps track of total ray length dist_to_nearest = distance_transform(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt) total_dist += dist_to_nearest - + return total_dist + @njit(cache=True) -def get_scan(pose, theta_dis, fov, num_beams, theta_index_increment, sines, cosines, eps, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt, max_range): +def get_scan( + pose, + theta_dis, + fov, + num_beams, + theta_index_increment, + sines, + cosines, + eps, + orig_x, + orig_y, + orig_c, + orig_s, + height, + width, + resolution, + dt, + max_range, +): """ Perform the scan for each discretized angle of each beam of the laser, loop heavy, should be JITted @@ -137,17 +162,33 @@ def get_scan(pose, theta_dis, fov, num_beams, theta_index_increment, sines, cosi scan = np.empty((num_beams,)) # make theta discrete by mapping the range [-pi, pi] onto [0, theta_dis] - theta_index = theta_dis * (pose[2] - fov/2.)/(2. * np.pi) + theta_index = theta_dis * (pose[2] - fov / 2.0) / (2.0 * np.pi) # make sure it's wrapped properly theta_index = np.fmod(theta_index, theta_dis) - while (theta_index < 0): + while theta_index < 0: theta_index += theta_dis # sweep through each beam for i in range(0, num_beams): # trace the current beam - scan[i] = trace_ray(pose[0], pose[1], theta_index, sines, cosines, eps, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt, max_range) + scan[i] = trace_ray( + pose[0], + pose[1], + theta_index, + sines, + cosines, + eps, + orig_x, + orig_y, + orig_c, + orig_s, + height, + width, + resolution, + dt, + max_range, + ) # increment the beam index theta_index += theta_index_increment @@ -158,6 +199,7 @@ def get_scan(pose, theta_dis, fov, num_beams, theta_index_increment, sines, cosi return scan + class ScanSimulator2D(object): """ 2D LIDAR scan simulator class @@ -173,7 +215,7 @@ class ScanSimulator2D(object): """ def __init__(self, num_beams, fov, std_dev=0.01, eps=0.0001, theta_dis=2000, max_range=30.0, seed=123): - # initialization + # initialization self.num_beams = num_beams self.fov = fov self.std_dev = std_dev @@ -181,7 +223,7 @@ def __init__(self, num_beams, fov, std_dev=0.01, eps=0.0001, theta_dis=2000, max self.theta_dis = theta_dis self.max_range = max_range self.angle_increment = self.fov / (self.num_beams - 1) - self.theta_index_increment = theta_dis * self.angle_increment / (2. * np.pi) + self.theta_index_increment = theta_dis * self.angle_increment / (2.0 * np.pi) self.orig_c = None self.orig_s = None self.orig_x = None @@ -190,15 +232,15 @@ def __init__(self, num_beams, fov, std_dev=0.01, eps=0.0001, theta_dis=2000, max self.map_width = None self.map_resolution = None self.dt = None - + # white noise generator self.rng = np.random.default_rng(seed=seed) # precomputing corresponding cosines and sines of the angle array - theta_arr = np.linspace(0.0, 2*np.pi, num=theta_dis) + theta_arr = np.linspace(0.0, 2 * np.pi, num=theta_dis) self.sines = np.sin(theta_arr) self.cosines = np.cos(theta_arr) - + def set_map(self, map_path, map_ext): """ Set the bitmap of the scan simulator by path @@ -219,18 +261,18 @@ def set_map(self, map_path, map_ext): self.map_img = self.map_img.astype(np.float64) # grayscale -> binary - self.map_img[self.map_img <= 128.] = 0. - self.map_img[self.map_img > 128.] = 255. + self.map_img[self.map_img <= 128.0] = 0.0 + self.map_img[self.map_img > 128.0] = 255.0 self.map_height = self.map_img.shape[0] self.map_width = self.map_img.shape[1] # load map yaml - with open(map_path, 'r') as yaml_stream: + with open(map_path, "r") as yaml_stream: try: map_metadata = yaml.safe_load(yaml_stream) - self.map_resolution = map_metadata['resolution'] - self.origin = map_metadata['origin'] + self.map_resolution = map_metadata["resolution"] + self.origin = map_metadata["origin"] except yaml.YAMLError as ex: print(ex) @@ -259,9 +301,27 @@ def scan(self, pose): ValueError: when scan is called before a map is set """ if self.map_height is None: - raise ValueError('Map is not set for scan simulator.') - scan = get_scan(pose, self.theta_dis, self.fov, self.num_beams, self.theta_index_increment, self.sines, self.cosines, self.eps, self.orig_x, self.orig_y, self.orig_c, self.orig_s, self.map_height, self.map_width, self.map_resolution, self.dt, self.max_range) - noise = self.rng.normal(0., self.std_dev, size=self.num_beams) + raise ValueError("Map is not set for scan simulator.") + scan = get_scan( + pose, + self.theta_dis, + self.fov, + self.num_beams, + self.theta_index_increment, + self.sines, + self.cosines, + self.eps, + self.orig_x, + self.orig_y, + self.orig_c, + self.orig_s, + self.map_height, + self.map_width, + self.map_resolution, + self.dt, + self.max_range, + ) + noise = self.rng.normal(0.0, self.std_dev, size=self.num_beams) final_scan = scan + noise return final_scan @@ -284,26 +344,26 @@ def setUp(self): # test params self.num_beams = 1080 self.fov = 4.7 - + self.num_test = 10 self.test_poses = np.zeros((self.num_test, 3)) - self.test_poses[:, 2] = np.linspace(-1., 1., num=self.num_test) + self.test_poses[:, 2] = np.linspace(-1.0, 1.0, num=self.num_test) # legacy gym data - sample_scan = np.load('tests/legacy_scan.npz') - self.berlin_scan = sample_scan['berlin'] - self.skirk_scan = sample_scan['skirk'] + sample_scan = np.load("tests/legacy_scan.npz") + self.berlin_scan = sample_scan["berlin"] + self.skirk_scan = sample_scan["skirk"] def test_map_berlin(self, debug=False): scan_sim = ScanSimulator2D(self.num_beams, self.fov) new_berlin = np.empty((self.num_test, self.num_beams)) - map_path = '../../../maps/berlin.yaml' - map_ext = '.png' + map_path = "../../../maps/berlin.yaml" + map_ext = ".png" scan_sim.set_map(map_path, map_ext) # scan gen loop for i in range(self.num_test): test_pose = self.test_poses[i] - new_berlin[i,:] = scan_sim.scan(test_pose) + new_berlin[i, :] = scan_sim.scan(test_pose) diff = self.berlin_scan - new_berlin mse = np.mean(diff**2) # print('Levine distance test, norm: ' + str(norm)) @@ -311,98 +371,106 @@ def test_map_berlin(self, debug=False): if debug: # plotting import matplotlib.pyplot as plt - theta = np.linspace(-self.fov/2., self.fov/2., num=self.num_beams) - plt.polar(theta, new_berlin[1,:], '.', lw=0) - plt.polar(theta, self.berlin_scan[1,:], '.', lw=0) + + theta = np.linspace(-self.fov / 2.0, self.fov / 2.0, num=self.num_beams) + plt.polar(theta, new_berlin[1, :], ".", lw=0) + plt.polar(theta, self.berlin_scan[1, :], ".", lw=0) plt.show() - self.assertLess(mse, 2.) + self.assertLess(mse, 2.0) def test_map_skirk(self, debug=False): scan_sim = ScanSimulator2D(self.num_beams, self.fov) new_skirk = np.empty((self.num_test, self.num_beams)) - map_path = '../../../maps/skirk.yaml' - map_ext = '.png' + map_path = "../../../maps/skirk.yaml" + map_ext = ".png" scan_sim.set_map(map_path, map_ext) - print('map set') + print("map set") # scan gen loop for i in range(self.num_test): test_pose = self.test_poses[i] - new_skirk[i,:] = scan_sim.scan(test_pose) + new_skirk[i, :] = scan_sim.scan(test_pose) diff = self.skirk_scan - new_skirk mse = np.mean(diff**2) - print('skirk distance test, mse: ' + str(mse)) + print("skirk distance test, mse: " + str(mse)) if debug: # plotting import matplotlib.pyplot as plt - theta = np.linspace(-self.fov/2., self.fov/2., num=self.num_beams) - plt.polar(theta, new_skirk[1,:], '.', lw=0) - plt.polar(theta, self.skirk_scan[1,:], '.', lw=0) + + theta = np.linspace(-self.fov / 2.0, self.fov / 2.0, num=self.num_beams) + plt.polar(theta, new_skirk[1, :], ".", lw=0) + plt.polar(theta, self.skirk_scan[1, :], ".", lw=0) plt.show() - self.assertLess(mse, 2.) + self.assertLess(mse, 2.0) def test_fps(self): # scan fps should be greater than 500 scan_sim = ScanSimulator2D(self.num_beams, self.fov) - map_path = '../../../maps/skirk.yaml' - map_ext = '.png' + map_path = "../../../maps/skirk.yaml" + map_ext = ".png" scan_sim.set_map(map_path, map_ext) - + import time + start = time.time() for i in range(10000): - x_test = i/10000 - scan = scan_sim.scan(np.array([x_test, 0., 0.])) + x_test = i / 10000 + scan = scan_sim.scan(np.array([x_test, 0.0, 0.0])) end = time.time() - fps = 10000/(end-start) + fps = 10000 / (end - start) # print('FPS test') # print('Elapsed time: ' + str(end-start) + ' , FPS: ' + str(1/fps)) - self.assertGreater(fps, 500.) + self.assertGreater(fps, 500.0) def main(): num_beams = 1080 fov = 4.7 # map_path = '../envs/maps/berlin.yaml' - map_path = '/home/f1tenth-eval/tunercar/es/maps/map0.yaml' - map_ext = '.png' + map_path = "/home/f1tenth-eval/tunercar/es/maps/map0.yaml" + map_ext = ".png" scan_sim = ScanSimulator2D(num_beams, fov) scan_sim.set_map(map_path, map_ext) - scan = scan_sim.scan(np.array([0., 0., 0.])) + scan = scan_sim.scan(np.array([0.0, 0.0, 0.0])) # fps test import time + start = time.time() for i in range(10000): - x_test = i/10000 - scan = scan_sim.scan(np.array([x_test, 0., 0.])) + x_test = i / 10000 + scan = scan_sim.scan(np.array([x_test, 0.0, 0.0])) end = time.time() - fps = (end-start)/10000 - print('FPS test') - print('Elapsed time: ' + str(end-start) + ' , FPS: ' + str(1/fps)) + fps = (end - start) / 10000 + print("FPS test") + print("Elapsed time: " + str(end - start) + " , FPS: " + str(1 / fps)) # visualization import matplotlib.pyplot as plt from matplotlib.animation import FuncAnimation + num_iter = 100 - theta = np.linspace(-fov/2., fov/2., num=num_beams) + theta = np.linspace(-fov / 2.0, fov / 2.0, num=num_beams) fig = plt.figure() - ax = fig.add_subplot(111, projection='polar') + ax = fig.add_subplot(111, projection="polar") ax.set_ylim(0, 70) - line, = ax.plot([], [], '.', lw=0) + (line,) = ax.plot([], [], ".", lw=0) + def update(i): # x_ani = i * 3. / num_iter theta_ani = -i * 2 * np.pi / num_iter - x_ani = 0. - current_scan = scan_sim.scan(np.array([x_ani, 0., theta_ani])) + x_ani = 0.0 + current_scan = scan_sim.scan(np.array([x_ani, 0.0, theta_ani])) print(np.max(current_scan)) line.set_data(theta, current_scan) - return line, + return (line,) + ani = FuncAnimation(fig, update, frames=num_iter, blit=True) plt.show() -if __name__ == '__main__': + +if __name__ == "__main__": unittest.main() - #main() \ No newline at end of file + # main() From 9acf40deb97c9de23c6e94c9c3a33a5e0f0de4bc Mon Sep 17 00:00:00 2001 From: Nandan Tumu Date: Thu, 6 Jul 2023 14:37:25 -0700 Subject: [PATCH 08/32] refactored tests --- gym/f110_gym/envs/dynamic_models.py | 197 ---------------------------- 1 file changed, 197 deletions(-) diff --git a/gym/f110_gym/envs/dynamic_models.py b/gym/f110_gym/envs/dynamic_models.py index 25518052..531eed44 100644 --- a/gym/f110_gym/envs/dynamic_models.py +++ b/gym/f110_gym/envs/dynamic_models.py @@ -207,200 +207,3 @@ def func_KS(x, t, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_m def func_ST(x, t, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): f = vehicle_dynamics_st(x, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max) return f - -class DynamicsTest(unittest.TestCase): - def setUp(self): - # test params - self.mu = 1.0489 - self.C_Sf = 21.92/1.0489 - self.C_Sr = 21.92/1.0489 - self.lf = 0.3048*3.793293 - self.lr = 0.3048*4.667707 - self.h = 0.3048*2.01355 - self.m = 4.4482216152605/0.3048*74.91452 - self.I = 4.4482216152605*0.3048*1321.416 - - #steering constraints - self.s_min = -1.066 #minimum steering angle [rad] - self.s_max = 1.066 #maximum steering angle [rad] - self.sv_min = -0.4 #minimum steering velocity [rad/s] - self.sv_max = 0.4 #maximum steering velocity [rad/s] - - #longitudinal constraints - self.v_min = -13.6 #minimum velocity [m/s] - self.v_max = 50.8 #minimum velocity [m/s] - self.v_switch = 7.319 #switching velocity [m/s] - self.a_max = 11.5 #maximum absolute acceleration [m/s^2] - - def test_derivatives(self): - # ground truth derivatives - f_ks_gt = [16.3475935934250209, 0.4819314886013121, 0.1500000000000000, 5.1464424102339752, 0.2401426578627629] - f_st_gt = [15.7213512030862397, 0.0925527979719355, 0.1500000000000000, 5.3536773276413925, 0.0529001056654038, 0.6435589397748606, 0.0313297971641291] - - # system dynamics - g = 9.81 - x_ks = np.array([3.9579422297936526, 0.0391650102771405, 0.0378491427211811, 16.3546957860883566, 0.0294717351052816]) - x_st = np.array([2.0233348142065677, 0.0041907137716636, 0.0197545248559617, 15.7216236334290116, 0.0025857914776859, 0.0529001056654038, 0.0033012170610298]) - v_delta = 0.15 - acc = 0.63*g - u = np.array([v_delta, acc]) - - f_ks = vehicle_dynamics_ks(x_ks, u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max) - f_st = vehicle_dynamics_st(x_st, u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max) - - start = time.time() - for i in range(10000): - f_st = vehicle_dynamics_st(x_st, u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max) - duration = time.time() - start - avg_fps = 10000/duration - - self.assertAlmostEqual(np.max(np.abs(f_ks_gt-f_ks)), 0.) - self.assertAlmostEqual(np.max(np.abs(f_st_gt-f_st)), 0.) - self.assertGreater(avg_fps, 5000) - - def test_zeroinit_roll(self): - from scipy.integrate import odeint - - # testing for zero initial state, zero input singularities - g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set input: rolling car (velocity should stay constant) - u = np.array([0., 0.]) - - # simulate single-track model - x_roll_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - # simulate kinematic single-track model - x_roll_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - - self.assertTrue(all(x_roll_st[-1]==x0_ST)) - self.assertTrue(all(x_roll_ks[-1]==x0_KS)) - - def test_zeroinit_dec(self): - from scipy.integrate import odeint - - # testing for zero initial state, decelerating input singularities - g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set decel input - u = np.array([0., -0.7*g]) - - # simulate single-track model - x_dec_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - # simulate kinematic single-track model - x_dec_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - - # ground truth for single-track model - x_dec_st_gt = [-3.4335000000000013, 0.0000000000000000, 0.0000000000000000, -6.8670000000000018, 0.0000000000000000, 0.0000000000000000, 0.0000000000000000] - # ground truth for kinematic single-track model - x_dec_ks_gt = [-3.4335000000000013, 0.0000000000000000, 0.0000000000000000, -6.8670000000000018, 0.0000000000000000] - - self.assertTrue(all(abs(x_dec_st[-1] - x_dec_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_dec_ks[-1] - x_dec_ks_gt) < 1e-2)) - - def test_zeroinit_acc(self): - from scipy.integrate import odeint - - # testing for zero initial state, accelerating with left steer input singularities - # wheel spin and velocity should increase more wheel spin at rear - g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set decel input - u = np.array([0.15, 0.63*g]) - - # simulate single-track model - x_acc_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - # simulate kinematic single-track model - x_acc_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - - # ground truth for single-track model - x_acc_st_gt = [3.0731976046859715, 0.2869835398304389, 0.1500000000000000, 6.1802999999999999, 0.1097747074946325, 0.3248268063223301, 0.0697547542798040] - # ground truth for kinematic single-track model - x_acc_ks_gt = [3.0845676868494927, 0.1484249221523042, 0.1500000000000000, 6.1803000000000017, 0.1203664469224163] - - self.assertTrue(all(abs(x_acc_st[-1] - x_acc_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_acc_ks[-1] - x_acc_ks_gt) < 1e-2)) - - def test_zeroinit_rollleft(self): - from scipy.integrate import odeint - - # testing for zero initial state, rolling and steering left input singularities - g = 9.81 - t_start = 0. - t_final = 1. - delta0 = 0. - vel0 = 0. - Psi0 = 0. - dotPsi0 = 0. - beta0 = 0. - sy0 = 0. - initial_state = [0,sy0,delta0,vel0,Psi0,dotPsi0,beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set decel input - u = np.array([0.15, 0.]) - - # simulate single-track model - x_left_st = odeint(func_ST, x0_ST, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - # simulate kinematic single-track model - x_left_ks = odeint(func_KS, x0_KS, t, args=(u, self.mu, self.C_Sf, self.C_Sr, self.lf, self.lr, self.h, self.m, self.I, self.s_min, self.s_max, self.sv_min, self.sv_max, self.v_switch, self.a_max, self.v_min, self.v_max)) - - # ground truth for single-track model - x_left_st_gt = [0.0000000000000000, 0.0000000000000000, 0.1500000000000000, 0.0000000000000000, 0.0000000000000000, 0.0000000000000000, 0.0000000000000000] - # ground truth for kinematic single-track model - x_left_ks_gt = [0.0000000000000000, 0.0000000000000000, 0.1500000000000000, 0.0000000000000000, 0.0000000000000000] - - self.assertTrue(all(abs(x_left_st[-1] - x_left_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_left_ks[-1] - x_left_ks_gt) < 1e-2)) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file From 432b135e2464abc449bd09dc0122209dcc24cb26 Mon Sep 17 00:00:00 2001 From: Nandan Tumu <10603428+nandantumu@users.noreply.github.com> Date: Fri, 7 Jul 2023 21:22:10 -0400 Subject: [PATCH 09/32] Update README.md Added Linting Badge --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index 49025d46..deafba72 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,7 @@ ![Python 3.8 3.9](https://github.com/f1tenth/f1tenth_gym/actions/workflows/ci.yml/badge.svg) ![Docker](https://github.com/f1tenth/f1tenth_gym/actions/workflows/docker.yml/badge.svg) +![Code Style](https://github.com/f1tenth/f1tenth_gym/actions/workflows/lint.yml/badge.svg) + # The F1TENTH Gym environment This is the repository of the F1TENTH Gym environment. From b5e30bfd14da5fdc4d893805dfdfe2872ed4a7f9 Mon Sep 17 00:00:00 2001 From: Nandan Tumu <10603428+nandantumu@users.noreply.github.com> Date: Fri, 7 Jul 2023 21:22:52 -0400 Subject: [PATCH 10/32] Update lint.yml Added failure mode to badge --- .github/workflows/lint.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index b2b91fca..fff77426 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -41,4 +41,4 @@ jobs: run: | # stop the build if there are Python syntax errors or undefined names # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide - flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + flake8 . --count --max-complexity=10 --max-line-length=127 --statistics From 9886855771123d7da327f6e364d0a9964021585f Mon Sep 17 00:00:00 2001 From: nandantumu Date: Tue, 22 Aug 2023 19:33:05 -0400 Subject: [PATCH 11/32] Updated tests to run headless --- tests/legacy_scan_gen.py | 1 - tests/test_collision_checks.py | 18 ++-- tests/test_dynamics.py | 1 - tests/test_scan_sim.py | 158 ++++----------------------------- 4 files changed, 25 insertions(+), 153 deletions(-) diff --git a/tests/legacy_scan_gen.py b/tests/legacy_scan_gen.py index 96beed5a..93c97e56 100644 --- a/tests/legacy_scan_gen.py +++ b/tests/legacy_scan_gen.py @@ -36,7 +36,6 @@ import numpy as np import gym -import matplotlib.pyplot as plt thetas = np.linspace(-2.35, 2.35, num=1080) diff --git a/tests/test_collision_checks.py b/tests/test_collision_checks.py index 3d7b3cdd..e40e2f9c 100644 --- a/tests/test_collision_checks.py +++ b/tests/test_collision_checks.py @@ -264,18 +264,18 @@ def setUp(self): self.length = 0.32 self.width = 0.22 - def test_get_vert(self): + def test_get_vert(self, debug=False): test_pose = np.array([2.3, 6.7, 0.8]) vertices = get_vertices(test_pose, self.length, self.width) rect = np.vstack((vertices, vertices[0, :])) - import matplotlib.pyplot as plt - - plt.scatter(test_pose[0], test_pose[1], c="red") - plt.plot(rect[:, 0], rect[:, 1]) - plt.xlim([1, 4]) - plt.ylim([5, 8]) - plt.axes().set_aspect("equal") - plt.show() + if debug: + import matplotlib.pyplot as plt + plt.scatter(test_pose[0], test_pose[1], c="red") + plt.plot(rect[:, 0], rect[:, 1]) + plt.xlim([1, 4]) + plt.ylim([5, 8]) + plt.axes().set_aspect("equal") + plt.show() self.assertTrue(vertices.shape == (4, 2)) def test_get_vert_fps(self): diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 7bce8f43..56ee4889 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -20,7 +20,6 @@ """ import numpy as np -from numba import njit import unittest import time diff --git a/tests/test_scan_sim.py b/tests/test_scan_sim.py index 393b96d8..dab88b57 100644 --- a/tests/test_scan_sim.py +++ b/tests/test_scan_sim.py @@ -249,134 +249,6 @@ def get_scan( return scan -class ScanSimulator2D(object): - """ - 2D LIDAR scan simulator class - - Init params: - num_beams (int): number of beams in the scan - fov (float): field of view of the laser scan - std_dev (float, default=0.01): standard deviation of the generated whitenoise in the scan - eps (float, default=0.0001): ray tracing iteration termination condition - theta_dis (int, default=2000): number of steps to discretize the angles between 0 and 2pi for look up - max_range (float, default=30.0): maximum range of the laser - seed (int, default=123): seed for random number generator for the whitenoise in scan - """ - - def __init__(self, num_beams, fov, std_dev=0.01, eps=0.0001, theta_dis=2000, max_range=30.0, seed=123): - # initialization - self.num_beams = num_beams - self.fov = fov - self.std_dev = std_dev - self.eps = eps - self.theta_dis = theta_dis - self.max_range = max_range - self.angle_increment = self.fov / (self.num_beams - 1) - self.theta_index_increment = theta_dis * self.angle_increment / (2.0 * np.pi) - self.orig_c = None - self.orig_s = None - self.orig_x = None - self.orig_y = None - self.map_height = None - self.map_width = None - self.map_resolution = None - self.dt = None - - # white noise generator - self.rng = np.random.default_rng(seed=seed) - - # precomputing corresponding cosines and sines of the angle array - theta_arr = np.linspace(0.0, 2 * np.pi, num=theta_dis) - self.sines = np.sin(theta_arr) - self.cosines = np.cos(theta_arr) - - def set_map(self, map_path, map_ext): - """ - Set the bitmap of the scan simulator by path - - Args: - map_path (str): path to the map yaml file - map_ext (str): extension (image type) of the map image - - Returns: - flag (bool): if image reading and loading is successful - """ - # TODO: do we open the option to flip the images, and turn rgb into grayscale? or specify the exact requirements in documentation. - # TODO: throw error if image specification isn't met - - # load map image - map_img_path = os.path.splitext(map_path)[0] + map_ext - self.map_img = np.array(Image.open(map_img_path).transpose(Image.FLIP_TOP_BOTTOM)) - self.map_img = self.map_img.astype(np.float64) - - # grayscale -> binary - self.map_img[self.map_img <= 128.0] = 0.0 - self.map_img[self.map_img > 128.0] = 255.0 - - self.map_height = self.map_img.shape[0] - self.map_width = self.map_img.shape[1] - - # load map yaml - with open(map_path, "r") as yaml_stream: - try: - map_metadata = yaml.safe_load(yaml_stream) - self.map_resolution = map_metadata["resolution"] - self.origin = map_metadata["origin"] - except yaml.YAMLError as ex: - print(ex) - - # calculate map parameters - self.orig_x = self.origin[0] - self.orig_y = self.origin[1] - self.orig_s = np.sin(self.origin[2]) - self.orig_c = np.cos(self.origin[2]) - - # get the distance transform - self.dt = get_dt(self.map_img, self.map_resolution) - - return True - - def scan(self, pose): - """ - Perform simulated 2D scan by pose on the given map - - Args: - pose (numpy.ndarray (3, )): pose of the scan frame (x, y, theta) - - Returns: - scan (numpy.ndarray (n, )): data array of the laserscan, n=num_beams - - Raises: - ValueError: when scan is called before a map is set - """ - if self.map_height is None: - raise ValueError("Map is not set for scan simulator.") - scan = get_scan( - pose, - self.theta_dis, - self.fov, - self.num_beams, - self.theta_index_increment, - self.sines, - self.cosines, - self.eps, - self.orig_x, - self.orig_y, - self.orig_c, - self.orig_s, - self.map_height, - self.map_width, - self.map_resolution, - self.dt, - self.max_range, - ) - noise = self.rng.normal(0.0, self.std_dev, size=self.num_beams) - final_scan = scan + noise - return final_scan - - def get_increment(self): - return self.angle_increment - """ Unit test for the 2D scan simulator class Author: Hongrui Zheng @@ -403,7 +275,7 @@ def setUp(self): self.berlin_scan = sample_scan["berlin"] self.skirk_scan = sample_scan["skirk"] - def test_map_berlin(self): + def test_map_berlin(self, debug=False): scan_rng = np.random.default_rng(seed=12345) scan_sim = ScanSimulator2D(self.num_beams, self.fov) new_berlin = np.empty((self.num_test, self.num_beams)) @@ -416,17 +288,18 @@ def test_map_berlin(self): mse = np.mean(diff**2) # print('Levine distance test, norm: ' + str(norm)) - # plotting - import matplotlib.pyplot as plt + if debug: + # plotting + import matplotlib.pyplot as plt - theta = np.linspace(-self.fov / 2.0, self.fov / 2.0, num=self.num_beams) - plt.polar(theta, new_berlin[1, :], ".", lw=0) - plt.polar(theta, self.berlin_scan[1, :], ".", lw=0) - plt.show() + theta = np.linspace(-self.fov / 2.0, self.fov / 2.0, num=self.num_beams) + plt.polar(theta, new_berlin[1, :], ".", lw=0) + plt.polar(theta, self.berlin_scan[1, :], ".", lw=0) + plt.show() self.assertLess(mse, 2.0) - def test_map_skirk(self): + def test_map_skirk(self, debug=False): scan_rng = np.random.default_rng(seed=12345) scan_sim = ScanSimulator2D(self.num_beams, self.fov) new_skirk = np.empty((self.num_test, self.num_beams)) @@ -440,13 +313,14 @@ def test_map_skirk(self): mse = np.mean(diff**2) print("skirk distance test, mse: " + str(mse)) - # plotting - import matplotlib.pyplot as plt + if debug: + # plotting + import matplotlib.pyplot as plt - theta = np.linspace(-self.fov / 2.0, self.fov / 2.0, num=self.num_beams) - plt.polar(theta, new_skirk[1, :], ".", lw=0) - plt.polar(theta, self.skirk_scan[1, :], ".", lw=0) - plt.show() + theta = np.linspace(-self.fov / 2.0, self.fov / 2.0, num=self.num_beams) + plt.polar(theta, new_skirk[1, :], ".", lw=0) + plt.polar(theta, self.skirk_scan[1, :], ".", lw=0) + plt.show() self.assertLess(mse, 2.0) From 4b0a126ff65640a98f940fcb52763843061b2c7d Mon Sep 17 00:00:00 2001 From: nandantumu Date: Tue, 22 Aug 2023 19:33:23 -0400 Subject: [PATCH 12/32] Updated Dependencies --- Pipfile | 17 +- Pipfile.lock | 1094 ++++++++++++++++++++++++++++++++++++++++++---- requirements.txt | 34 ++ setup.py | 2 +- 4 files changed, 1047 insertions(+), 100 deletions(-) create mode 100644 requirements.txt diff --git a/Pipfile b/Pipfile index 574c29c6..ff334207 100644 --- a/Pipfile +++ b/Pipfile @@ -4,14 +4,25 @@ verify_ssl = true name = "pypi" [packages] +gymnasium = "*" +numpy = "<1.25" +pillow = ">=9.0.1" +scipy = ">=1.7.3" +pyglet = "<1.5" +pyyaml = ">=5.3.1" +yamldataclassconfig = "*" +matplotlib = "*" +requests = "*" +pyopengl = "*" numba = "*" -pillow = "*" -scipy = "*" +f110-gym = {file = "."} [dev-packages] flake8 = "*" black = "*" +ipykernel = "*" +pytest = "*" [requires] python_version = "3.10" -python_full_version = "3.10.12" +python_full_version = "3.10.11" diff --git a/Pipfile.lock b/Pipfile.lock index 31a9ceb8..2f6fa17a 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,11 +1,11 @@ { "_meta": { "hash": { - "sha256": "d7937f644576260519209654eaa918509e1cda0420b9c530e59ea606a6c86a17" + "sha256": "cd0dd1f62d1aec40708cf8248298c17e0522dcdf12d80f78c2bc9e2a64f236f5" }, "pipfile-spec": 6, "requires": { - "python_full_version": "3.10.12", + "python_full_version": "3.10.11", "python_version": "3.10" }, "sources": [ @@ -17,6 +17,312 @@ ] }, "default": { + "certifi": { + "hashes": [ + "sha256:539cc1d13202e33ca466e88b2807e29f4c13049d6d87031a3c110744495cb082", + "sha256:92d6037539857d8206b8f6ae472e8b77db8058fec5937a1ef3f54304089edbb9" + ], + "markers": "python_version >= '3.6'", + "version": "==2023.7.22" + }, + "charset-normalizer": { + "hashes": [ + "sha256:04e57ab9fbf9607b77f7d057974694b4f6b142da9ed4a199859d9d4d5c63fe96", + "sha256:09393e1b2a9461950b1c9a45d5fd251dc7c6f228acab64da1c9c0165d9c7765c", + "sha256:0b87549028f680ca955556e3bd57013ab47474c3124dc069faa0b6545b6c9710", + "sha256:1000fba1057b92a65daec275aec30586c3de2401ccdcd41f8a5c1e2c87078706", + "sha256:1249cbbf3d3b04902ff081ffbb33ce3377fa6e4c7356f759f3cd076cc138d020", + "sha256:1920d4ff15ce893210c1f0c0e9d19bfbecb7983c76b33f046c13a8ffbd570252", + "sha256:193cbc708ea3aca45e7221ae58f0fd63f933753a9bfb498a3b474878f12caaad", + "sha256:1a100c6d595a7f316f1b6f01d20815d916e75ff98c27a01ae817439ea7726329", + "sha256:1f30b48dd7fa1474554b0b0f3fdfdd4c13b5c737a3c6284d3cdc424ec0ffff3a", + "sha256:203f0c8871d5a7987be20c72442488a0b8cfd0f43b7973771640fc593f56321f", + "sha256:246de67b99b6851627d945db38147d1b209a899311b1305dd84916f2b88526c6", + "sha256:2dee8e57f052ef5353cf608e0b4c871aee320dd1b87d351c28764fc0ca55f9f4", + "sha256:2efb1bd13885392adfda4614c33d3b68dee4921fd0ac1d3988f8cbb7d589e72a", + "sha256:2f4ac36d8e2b4cc1aa71df3dd84ff8efbe3bfb97ac41242fbcfc053c67434f46", + "sha256:3170c9399da12c9dc66366e9d14da8bf7147e1e9d9ea566067bbce7bb74bd9c2", + "sha256:3b1613dd5aee995ec6d4c69f00378bbd07614702a315a2cf6c1d21461fe17c23", + "sha256:3bb3d25a8e6c0aedd251753a79ae98a093c7e7b471faa3aa9a93a81431987ace", + "sha256:3bb7fda7260735efe66d5107fb7e6af6a7c04c7fce9b2514e04b7a74b06bf5dd", + "sha256:41b25eaa7d15909cf3ac4c96088c1f266a9a93ec44f87f1d13d4a0e86c81b982", + "sha256:45de3f87179c1823e6d9e32156fb14c1927fcc9aba21433f088fdfb555b77c10", + "sha256:46fb8c61d794b78ec7134a715a3e564aafc8f6b5e338417cb19fe9f57a5a9bf2", + "sha256:48021783bdf96e3d6de03a6e39a1171ed5bd7e8bb93fc84cc649d11490f87cea", + "sha256:4957669ef390f0e6719db3613ab3a7631e68424604a7b448f079bee145da6e09", + "sha256:5e86d77b090dbddbe78867a0275cb4df08ea195e660f1f7f13435a4649e954e5", + "sha256:6339d047dab2780cc6220f46306628e04d9750f02f983ddb37439ca47ced7149", + "sha256:681eb3d7e02e3c3655d1b16059fbfb605ac464c834a0c629048a30fad2b27489", + "sha256:6c409c0deba34f147f77efaa67b8e4bb83d2f11c8806405f76397ae5b8c0d1c9", + "sha256:7095f6fbfaa55defb6b733cfeb14efaae7a29f0b59d8cf213be4e7ca0b857b80", + "sha256:70c610f6cbe4b9fce272c407dd9d07e33e6bf7b4aa1b7ffb6f6ded8e634e3592", + "sha256:72814c01533f51d68702802d74f77ea026b5ec52793c791e2da806a3844a46c3", + "sha256:7a4826ad2bd6b07ca615c74ab91f32f6c96d08f6fcc3902ceeedaec8cdc3bcd6", + "sha256:7c70087bfee18a42b4040bb9ec1ca15a08242cf5867c58726530bdf3945672ed", + "sha256:855eafa5d5a2034b4621c74925d89c5efef61418570e5ef9b37717d9c796419c", + "sha256:8700f06d0ce6f128de3ccdbc1acaea1ee264d2caa9ca05daaf492fde7c2a7200", + "sha256:89f1b185a01fe560bc8ae5f619e924407efca2191b56ce749ec84982fc59a32a", + "sha256:8b2c760cfc7042b27ebdb4a43a4453bd829a5742503599144d54a032c5dc7e9e", + "sha256:8c2f5e83493748286002f9369f3e6607c565a6a90425a3a1fef5ae32a36d749d", + "sha256:8e098148dd37b4ce3baca71fb394c81dc5d9c7728c95df695d2dca218edf40e6", + "sha256:94aea8eff76ee6d1cdacb07dd2123a68283cb5569e0250feab1240058f53b623", + "sha256:95eb302ff792e12aba9a8b8f8474ab229a83c103d74a750ec0bd1c1eea32e669", + "sha256:9bd9b3b31adcb054116447ea22caa61a285d92e94d710aa5ec97992ff5eb7cf3", + "sha256:9e608aafdb55eb9f255034709e20d5a83b6d60c054df0802fa9c9883d0a937aa", + "sha256:a103b3a7069b62f5d4890ae1b8f0597618f628b286b03d4bc9195230b154bfa9", + "sha256:a386ebe437176aab38c041de1260cd3ea459c6ce5263594399880bbc398225b2", + "sha256:a38856a971c602f98472050165cea2cdc97709240373041b69030be15047691f", + "sha256:a401b4598e5d3f4a9a811f3daf42ee2291790c7f9d74b18d75d6e21dda98a1a1", + "sha256:a7647ebdfb9682b7bb97e2a5e7cb6ae735b1c25008a70b906aecca294ee96cf4", + "sha256:aaf63899c94de41fe3cf934601b0f7ccb6b428c6e4eeb80da72c58eab077b19a", + "sha256:b0dac0ff919ba34d4df1b6131f59ce95b08b9065233446be7e459f95554c0dc8", + "sha256:baacc6aee0b2ef6f3d308e197b5d7a81c0e70b06beae1f1fcacffdbd124fe0e3", + "sha256:bf420121d4c8dce6b889f0e8e4ec0ca34b7f40186203f06a946fa0276ba54029", + "sha256:c04a46716adde8d927adb9457bbe39cf473e1e2c2f5d0a16ceb837e5d841ad4f", + "sha256:c0b21078a4b56965e2b12f247467b234734491897e99c1d51cee628da9786959", + "sha256:c1c76a1743432b4b60ab3358c937a3fe1341c828ae6194108a94c69028247f22", + "sha256:c4983bf937209c57240cff65906b18bb35e64ae872da6a0db937d7b4af845dd7", + "sha256:c4fb39a81950ec280984b3a44f5bd12819953dc5fa3a7e6fa7a80db5ee853952", + "sha256:c57921cda3a80d0f2b8aec7e25c8aa14479ea92b5b51b6876d975d925a2ea346", + "sha256:c8063cf17b19661471ecbdb3df1c84f24ad2e389e326ccaf89e3fb2484d8dd7e", + "sha256:ccd16eb18a849fd8dcb23e23380e2f0a354e8daa0c984b8a732d9cfaba3a776d", + "sha256:cd6dbe0238f7743d0efe563ab46294f54f9bc8f4b9bcf57c3c666cc5bc9d1299", + "sha256:d62e51710986674142526ab9f78663ca2b0726066ae26b78b22e0f5e571238dd", + "sha256:db901e2ac34c931d73054d9797383d0f8009991e723dab15109740a63e7f902a", + "sha256:e03b8895a6990c9ab2cdcd0f2fe44088ca1c65ae592b8f795c3294af00a461c3", + "sha256:e1c8a2f4c69e08e89632defbfabec2feb8a8d99edc9f89ce33c4b9e36ab63037", + "sha256:e4b749b9cc6ee664a3300bb3a273c1ca8068c46be705b6c31cf5d276f8628a94", + "sha256:e6a5bf2cba5ae1bb80b154ed68a3cfa2fa00fde979a7f50d6598d3e17d9ac20c", + "sha256:e857a2232ba53ae940d3456f7533ce6ca98b81917d47adc3c7fd55dad8fab858", + "sha256:ee4006268ed33370957f55bf2e6f4d263eaf4dc3cfc473d1d90baff6ed36ce4a", + "sha256:eef9df1eefada2c09a5e7a40991b9fc6ac6ef20b1372abd48d2794a316dc0449", + "sha256:f058f6963fd82eb143c692cecdc89e075fa0828db2e5b291070485390b2f1c9c", + "sha256:f25c229a6ba38a35ae6e25ca1264621cc25d4d38dca2942a7fce0b67a4efe918", + "sha256:f2a1d0fd4242bd8643ce6f98927cf9c04540af6efa92323e9d3124f57727bfc1", + "sha256:f7560358a6811e52e9c4d142d497f1a6e10103d3a6881f18d04dbce3729c0e2c", + "sha256:f779d3ad205f108d14e99bb3859aa7dd8e9c68874617c72354d7ecaec2a054ac", + "sha256:f87f746ee241d30d6ed93969de31e5ffd09a2961a051e60ae6bddde9ec3583aa" + ], + "markers": "python_full_version >= '3.7.0'", + "version": "==3.2.0" + }, + "cloudpickle": { + "hashes": [ + "sha256:61f594d1f4c295fa5cd9014ceb3a1fc4a70b0de1164b94fbc2d854ccba056f9f", + "sha256:d89684b8de9e34a2a43b3460fbca07d09d6e25ce858df4d5a44240403b6178f5" + ], + "markers": "python_version >= '3.6'", + "version": "==2.2.1" + }, + "contourpy": { + "hashes": [ + "sha256:052cc634bf903c604ef1a00a5aa093c54f81a2612faedaa43295809ffdde885e", + "sha256:084eaa568400cfaf7179b847ac871582199b1b44d5699198e9602ecbbb5f6104", + "sha256:0b6616375d7de55797d7a66ee7d087efe27f03d336c27cf1f32c02b8c1a5ac70", + "sha256:0b7b04ed0961647691cfe5d82115dd072af7ce8846d31a5fac6c142dcce8b882", + "sha256:143dde50520a9f90e4a2703f367cf8ec96a73042b72e68fcd184e1279962eb6f", + "sha256:17cfaf5ec9862bc93af1ec1f302457371c34e688fbd381f4035a06cd47324f48", + "sha256:181cbace49874f4358e2929aaf7ba84006acb76694102e88dd15af861996c16e", + "sha256:189ceb1525eb0655ab8487a9a9c41f42a73ba52d6789754788d1883fb06b2d8a", + "sha256:18a64814ae7bce73925131381603fff0116e2df25230dfc80d6d690aa6e20b37", + "sha256:1f0cbd657e9bde94cd0e33aa7df94fb73c1ab7799378d3b3f902eb8eb2e04a3a", + "sha256:1f795597073b09d631782e7245016a4323cf1cf0b4e06eef7ea6627e06a37ff2", + "sha256:25ae46595e22f93592d39a7eac3d638cda552c3e1160255258b695f7b58e5655", + "sha256:27bc79200c742f9746d7dd51a734ee326a292d77e7d94c8af6e08d1e6c15d545", + "sha256:2b836d22bd2c7bb2700348e4521b25e077255ebb6ab68e351ab5aa91ca27e027", + "sha256:30f511c05fab7f12e0b1b7730ebdc2ec8deedcfb505bc27eb570ff47c51a8f15", + "sha256:317267d915490d1e84577924bd61ba71bf8681a30e0d6c545f577363157e5e94", + "sha256:397b0ac8a12880412da3551a8cb5a187d3298a72802b45a3bd1805e204ad8439", + "sha256:438ba416d02f82b692e371858143970ed2eb6337d9cdbbede0d8ad9f3d7dd17d", + "sha256:53cc3a40635abedbec7f1bde60f8c189c49e84ac180c665f2cd7c162cc454baa", + "sha256:5d123a5bc63cd34c27ff9c7ac1cd978909e9c71da12e05be0231c608048bb2ae", + "sha256:62013a2cf68abc80dadfd2307299bfa8f5aa0dcaec5b2954caeb5fa094171103", + "sha256:89f06eff3ce2f4b3eb24c1055a26981bffe4e7264acd86f15b97e40530b794bc", + "sha256:90c81f22b4f572f8a2110b0b741bb64e5a6427e0a198b2cdc1fbaf85f352a3aa", + "sha256:911ff4fd53e26b019f898f32db0d4956c9d227d51338fb3b03ec72ff0084ee5f", + "sha256:9382a1c0bc46230fb881c36229bfa23d8c303b889b788b939365578d762b5c18", + "sha256:9f2931ed4741f98f74b410b16e5213f71dcccee67518970c42f64153ea9313b9", + "sha256:a67259c2b493b00e5a4d0f7bfae51fb4b3371395e47d079a4446e9b0f4d70e76", + "sha256:a698c6a7a432789e587168573a864a7ea374c6be8d4f31f9d87c001d5a843493", + "sha256:bc00bb4225d57bff7ebb634646c0ee2a1298402ec10a5fe7af79df9a51c1bfd9", + "sha256:bcb41692aa09aeb19c7c213411854402f29f6613845ad2453d30bf421fe68fed", + "sha256:d4f26b25b4f86087e7d75e63212756c38546e70f2a92d2be44f80114826e1cd4", + "sha256:d551f3a442655f3dcc1285723f9acd646ca5858834efeab4598d706206b09c9f", + "sha256:dffcc2ddec1782dd2f2ce1ef16f070861af4fb78c69862ce0aab801495dda6a3", + "sha256:e53046c3863828d21d531cc3b53786e6580eb1ba02477e8681009b6aa0870b21", + "sha256:e5cec36c5090e75a9ac9dbd0ff4a8cf7cecd60f1b6dc23a374c7d980a1cd710e", + "sha256:e7a117ce7df5a938fe035cad481b0189049e8d92433b4b33aa7fc609344aafa1", + "sha256:e94bef2580e25b5fdb183bf98a2faa2adc5b638736b2c0a4da98691da641316a", + "sha256:ed614aea8462735e7d70141374bd7650afd1c3f3cb0c2dbbcbe44e14331bf002", + "sha256:fb3b7d9e6243bfa1efb93ccfe64ec610d85cfe5aec2c25f97fbbd2e58b531256" + ], + "markers": "python_version >= '3.8'", + "version": "==1.1.0" + }, + "cycler": { + "hashes": [ + "sha256:3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3", + "sha256:9c87405839a19696e837b3b818fed3f5f69f16f1eec1a1ad77e043dcea9c772f" + ], + "markers": "python_version >= '3.6'", + "version": "==0.11.0" + }, + "dataclasses-json": { + "hashes": [ + "sha256:5ec6fed642adb1dbdb4182badb01e0861badfd8fda82e3b67f44b2d1e9d10d21", + "sha256:d82896a94c992ffaf689cd1fafc180164e2abdd415b8f94a7f78586af5886236" + ], + "markers": "python_version < '3.13' and python_version >= '3.7'", + "version": "==0.5.14" + }, + "f110-gym": { + "file": "." + }, + "farama-notifications": { + "hashes": [ + "sha256:13fceff2d14314cf80703c8266462ebf3733c7d165336eee998fc58e545efd18", + "sha256:14de931035a41961f7c056361dc7f980762a143d05791ef5794a751a2caf05ae" + ], + "version": "==0.0.4" + }, + "fonttools": { + "hashes": [ + "sha256:0eb79a2da5eb6457a6f8ab904838454accc7d4cccdaff1fd2bd3a0679ea33d64", + "sha256:113337c2d29665839b7d90b39f99b3cac731f72a0eda9306165a305c7c31d341", + "sha256:12a7c247d1b946829bfa2f331107a629ea77dc5391dfd34fdcd78efa61f354ca", + "sha256:179737095eb98332a2744e8f12037b2977f22948cf23ff96656928923ddf560a", + "sha256:19b7db825c8adee96fac0692e6e1ecd858cae9affb3b4812cdb9d934a898b29e", + "sha256:37983b6bdab42c501202500a2be3a572f50d4efe3237e0686ee9d5f794d76b35", + "sha256:3a35981d90feebeaef05e46e33e6b9e5b5e618504672ca9cd0ff96b171e4bfff", + "sha256:46a0ec8adbc6ff13494eb0c9c2e643b6f009ce7320cf640de106fb614e4d4360", + "sha256:4aa79366e442dbca6e2c8595645a3a605d9eeabdb7a094d745ed6106816bef5d", + "sha256:515607ec756d7865f23070682622c49d922901943697871fc292277cf1e71967", + "sha256:53eb5091ddc8b1199330bb7b4a8a2e7995ad5d43376cadce84523d8223ef3136", + "sha256:5d18fc642fd0ac29236ff88ecfccff229ec0386090a839dd3f1162e9a7944a40", + "sha256:5fb289b7a815638a7613d46bcf324c9106804725b2bb8ad913c12b6958ffc4ec", + "sha256:62f481ac772fd68901573956231aea3e4b1ad87b9b1089a61613a91e2b50bb9b", + "sha256:689508b918332fb40ce117131633647731d098b1b10d092234aa959b4251add5", + "sha256:68a02bbe020dc22ee0540e040117535f06df9358106d3775e8817d826047f3fd", + "sha256:6ed2662a3d9c832afa36405f8748c250be94ae5dfc5283d668308391f2102861", + "sha256:7286aed4ea271df9eab8d7a9b29e507094b51397812f7ce051ecd77915a6e26b", + "sha256:7cc7d685b8eeca7ae69dc6416833fbfea61660684b7089bca666067cb2937dcf", + "sha256:8708b98c278012ad267ee8a7433baeb809948855e81922878118464b274c909d", + "sha256:9398f244e28e0596e2ee6024f808b06060109e33ed38dcc9bded452fd9bbb853", + "sha256:9e36344e48af3e3bde867a1ca54f97c308735dd8697005c2d24a86054a114a71", + "sha256:a398bdadb055f8de69f62b0fc70625f7cbdab436bbb31eef5816e28cab083ee8", + "sha256:acb47f6f8680de24c1ab65ebde39dd035768e2a9b571a07c7b8da95f6c8815fd", + "sha256:be24fcb80493b2c94eae21df70017351851652a37de514de553435b256b2f249", + "sha256:c391cd5af88aacaf41dd7cfb96eeedfad297b5899a39e12f4c2c3706d0a3329d", + "sha256:c95b0724a6deea2c8c5d3222191783ced0a2f09bd6d33f93e563f6f1a4b3b3a4", + "sha256:c9b1ce7a45978b821a06d375b83763b27a3a5e8a2e4570b3065abad240a18760", + "sha256:db372213d39fa33af667c2aa586a0c1235e88e9c850f5dd5c8e1f17515861868", + "sha256:db55cbaea02a20b49fefbd8e9d62bd481aaabe1f2301dabc575acc6b358874fa", + "sha256:ed1a13a27f59d1fc1920394a7f596792e9d546c9ca5a044419dca70c37815d7c", + "sha256:f2b82f46917d8722e6b5eafeefb4fb585d23babd15d8246c664cd88a5bddd19c", + "sha256:f2f806990160d1ce42d287aa419df3ffc42dfefe60d473695fb048355fe0c6a0", + "sha256:f720fa82a11c0f9042376fd509b5ed88dab7e3cd602eee63a1af08883b37342b" + ], + "markers": "python_version >= '3.8'", + "version": "==4.42.1" + }, + "future": { + "hashes": [ + "sha256:34a17436ed1e96697a86f9de3d15a3b0be01d8bc8de9c1dffd59fb8234ed5307" + ], + "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==0.18.3" + }, + "gymnasium": { + "hashes": [ + "sha256:1a532752efcb7590478b1cc7aa04f608eb7a2fdad5570cd217b66b6a35274bb1", + "sha256:61c3384b5575985bb7f85e43213bcb40f36fcdff388cae6bc229304c71f2843e" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==0.29.1" + }, + "idna": { + "hashes": [ + "sha256:814f528e8dead7d329833b91c5faa87d60bf71824cd12a7530b5526063d02cb4", + "sha256:90b77e79eaa3eba6de819a0c442c0b4ceefc341a7a2ab77d7562bf49f425c5c2" + ], + "markers": "python_version >= '3.5'", + "version": "==3.4" + }, + "kiwisolver": { + "hashes": [ + "sha256:02f79693ec433cb4b5f51694e8477ae83b3205768a6fb48ffba60549080e295b", + "sha256:03baab2d6b4a54ddbb43bba1a3a2d1627e82d205c5cf8f4c924dc49284b87166", + "sha256:1041feb4cda8708ce73bb4dcb9ce1ccf49d553bf87c3954bdfa46f0c3f77252c", + "sha256:10ee06759482c78bdb864f4109886dff7b8a56529bc1609d4f1112b93fe6423c", + "sha256:1d1573129aa0fd901076e2bfb4275a35f5b7aa60fbfb984499d661ec950320b0", + "sha256:283dffbf061a4ec60391d51e6155e372a1f7a4f5b15d59c8505339454f8989e4", + "sha256:28bc5b299f48150b5f822ce68624e445040595a4ac3d59251703779836eceff9", + "sha256:2a66fdfb34e05b705620dd567f5a03f239a088d5a3f321e7b6ac3239d22aa286", + "sha256:2e307eb9bd99801f82789b44bb45e9f541961831c7311521b13a6c85afc09767", + "sha256:2e407cb4bd5a13984a6c2c0fe1845e4e41e96f183e5e5cd4d77a857d9693494c", + "sha256:2f5e60fabb7343a836360c4f0919b8cd0d6dbf08ad2ca6b9cf90bf0c76a3c4f6", + "sha256:36dafec3d6d6088d34e2de6b85f9d8e2324eb734162fba59d2ba9ed7a2043d5b", + "sha256:3fe20f63c9ecee44560d0e7f116b3a747a5d7203376abeea292ab3152334d004", + "sha256:41dae968a94b1ef1897cb322b39360a0812661dba7c682aa45098eb8e193dbdf", + "sha256:4bd472dbe5e136f96a4b18f295d159d7f26fd399136f5b17b08c4e5f498cd494", + "sha256:4ea39b0ccc4f5d803e3337dd46bcce60b702be4d86fd0b3d7531ef10fd99a1ac", + "sha256:5853eb494c71e267912275e5586fe281444eb5e722de4e131cddf9d442615626", + "sha256:5bce61af018b0cb2055e0e72e7d65290d822d3feee430b7b8203d8a855e78766", + "sha256:6295ecd49304dcf3bfbfa45d9a081c96509e95f4b9d0eb7ee4ec0530c4a96514", + "sha256:62ac9cc684da4cf1778d07a89bf5f81b35834cb96ca523d3a7fb32509380cbf6", + "sha256:70e7c2e7b750585569564e2e5ca9845acfaa5da56ac46df68414f29fea97be9f", + "sha256:7577c1987baa3adc4b3c62c33bd1118c3ef5c8ddef36f0f2c950ae0b199e100d", + "sha256:75facbe9606748f43428fc91a43edb46c7ff68889b91fa31f53b58894503a191", + "sha256:787518a6789009c159453da4d6b683f468ef7a65bbde796bcea803ccf191058d", + "sha256:78d6601aed50c74e0ef02f4204da1816147a6d3fbdc8b3872d263338a9052c51", + "sha256:7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f", + "sha256:81e38381b782cc7e1e46c4e14cd997ee6040768101aefc8fa3c24a4cc58e98f8", + "sha256:841293b17ad704d70c578f1f0013c890e219952169ce8a24ebc063eecf775454", + "sha256:872b8ca05c40d309ed13eb2e582cab0c5a05e81e987ab9c521bf05ad1d5cf5cb", + "sha256:877272cf6b4b7e94c9614f9b10140e198d2186363728ed0f701c6eee1baec1da", + "sha256:8c808594c88a025d4e322d5bb549282c93c8e1ba71b790f539567932722d7bd8", + "sha256:8ed58b8acf29798b036d347791141767ccf65eee7f26bde03a71c944449e53de", + "sha256:91672bacaa030f92fc2f43b620d7b337fd9a5af28b0d6ed3f77afc43c4a64b5a", + "sha256:968f44fdbf6dd757d12920d63b566eeb4d5b395fd2d00d29d7ef00a00582aac9", + "sha256:9f85003f5dfa867e86d53fac6f7e6f30c045673fa27b603c397753bebadc3008", + "sha256:a553dadda40fef6bfa1456dc4be49b113aa92c2a9a9e8711e955618cd69622e3", + "sha256:a68b62a02953b9841730db7797422f983935aeefceb1679f0fc85cbfbd311c32", + "sha256:abbe9fa13da955feb8202e215c4018f4bb57469b1b78c7a4c5c7b93001699938", + "sha256:ad881edc7ccb9d65b0224f4e4d05a1e85cf62d73aab798943df6d48ab0cd79a1", + "sha256:b1792d939ec70abe76f5054d3f36ed5656021dcad1322d1cc996d4e54165cef9", + "sha256:b428ef021242344340460fa4c9185d0b1f66fbdbfecc6c63eff4b7c29fad429d", + "sha256:b533558eae785e33e8c148a8d9921692a9fe5aa516efbdff8606e7d87b9d5824", + "sha256:ba59c92039ec0a66103b1d5fe588fa546373587a7d68f5c96f743c3396afc04b", + "sha256:bc8d3bd6c72b2dd9decf16ce70e20abcb3274ba01b4e1c96031e0c4067d1e7cd", + "sha256:bc9db8a3efb3e403e4ecc6cd9489ea2bac94244f80c78e27c31dcc00d2790ac2", + "sha256:bf7d9fce9bcc4752ca4a1b80aabd38f6d19009ea5cbda0e0856983cf6d0023f5", + "sha256:c2dbb44c3f7e6c4d3487b31037b1bdbf424d97687c1747ce4ff2895795c9bf69", + "sha256:c79ebe8f3676a4c6630fd3f777f3cfecf9289666c84e775a67d1d358578dc2e3", + "sha256:c97528e64cb9ebeff9701e7938653a9951922f2a38bd847787d4a8e498cc83ae", + "sha256:d0611a0a2a518464c05ddd5a3a1a0e856ccc10e67079bb17f265ad19ab3c7597", + "sha256:d06adcfa62a4431d404c31216f0f8ac97397d799cd53800e9d3efc2fbb3cf14e", + "sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955", + "sha256:d5b61785a9ce44e5a4b880272baa7cf6c8f48a5180c3e81c59553ba0cb0821ca", + "sha256:da152d8cdcab0e56e4f45eb08b9aea6455845ec83172092f09b0e077ece2cf7a", + "sha256:da7e547706e69e45d95e116e6939488d62174e033b763ab1496b4c29b76fabea", + "sha256:db5283d90da4174865d520e7366801a93777201e91e79bacbac6e6927cbceede", + "sha256:db608a6757adabb32f1cfe6066e39b3706d8c3aa69bbc353a5b61edad36a5cb4", + "sha256:e0ea21f66820452a3f5d1655f8704a60d66ba1191359b96541eaf457710a5fc6", + "sha256:e7da3fec7408813a7cebc9e4ec55afed2d0fd65c4754bc376bf03498d4e92686", + "sha256:e92a513161077b53447160b9bd8f522edfbed4bd9759e4c18ab05d7ef7e49408", + "sha256:ecb1fa0db7bf4cff9dac752abb19505a233c7f16684c5826d1f11ebd9472b871", + "sha256:efda5fc8cc1c61e4f639b8067d118e742b812c930f708e6667a5ce0d13499e29", + "sha256:f0a1dbdb5ecbef0d34eb77e56fcb3e95bbd7e50835d9782a45df81cc46949750", + "sha256:f0a71d85ecdd570ded8ac3d1c0f480842f49a40beb423bb8014539a9f32a5897", + "sha256:f4f270de01dd3e129a72efad823da90cc4d6aafb64c410c9033aba70db9f1ff0", + "sha256:f6cb459eea32a4e2cf18ba5fcece2dbdf496384413bc1bae15583f19e567f3b2", + "sha256:f8ad8285b01b0d4695102546b342b493b3ccc6781fc28c8c6a1bb63e95d22f09", + "sha256:f9f39e2f049db33a908319cf46624a569b36983c7c78318e9726a4cb8923b26c" + ], + "markers": "python_version >= '3.7'", + "version": "==1.4.4" + }, "llvmlite": { "hashes": [ "sha256:09f83ea7a54509c285f905d968184bba00fc31ebf12f2b6b1494d677bb7dde9b", @@ -47,6 +353,70 @@ "markers": "python_version >= '3.8'", "version": "==0.40.1" }, + "marshmallow": { + "hashes": [ + "sha256:5d2371bbe42000f2b3fb5eaa065224df7d8f8597bc19a1bbfa5bfe7fba8da889", + "sha256:684939db93e80ad3561392f47be0230743131560a41c5110684c16e21ade0a5c" + ], + "markers": "python_version >= '3.8'", + "version": "==3.20.1" + }, + "matplotlib": { + "hashes": [ + "sha256:070f8dddd1f5939e60aacb8fa08f19551f4b0140fab16a3669d5cd6e9cb28fc8", + "sha256:0c3cca3e842b11b55b52c6fb8bd6a4088693829acbfcdb3e815fa9b7d5c92c1b", + "sha256:0f506a1776ee94f9e131af1ac6efa6e5bc7cb606a3e389b0ccb6e657f60bb676", + "sha256:12f01b92ecd518e0697da4d97d163b2b3aa55eb3eb4e2c98235b3396d7dad55f", + "sha256:152ee0b569a37630d8628534c628456b28686e085d51394da6b71ef84c4da201", + "sha256:1c308b255efb9b06b23874236ec0f10f026673ad6515f602027cc8ac7805352d", + "sha256:1cd120fca3407a225168238b790bd5c528f0fafde6172b140a2f3ab7a4ea63e9", + "sha256:20f844d6be031948148ba49605c8b96dfe7d3711d1b63592830d650622458c11", + "sha256:23fb1750934e5f0128f9423db27c474aa32534cec21f7b2153262b066a581fd1", + "sha256:2699f7e73a76d4c110f4f25be9d2496d6ab4f17345307738557d345f099e07de", + "sha256:26bede320d77e469fdf1bde212de0ec889169b04f7f1179b8930d66f82b30cbc", + "sha256:2ecb5be2b2815431c81dc115667e33da0f5a1bcf6143980d180d09a717c4a12e", + "sha256:2f8e4a49493add46ad4a8c92f63e19d548b2b6ebbed75c6b4c7f46f57d36cdd1", + "sha256:305e3da477dc8607336ba10bac96986d6308d614706cae2efe7d3ffa60465b24", + "sha256:30e1409b857aa8a747c5d4f85f63a79e479835f8dffc52992ac1f3f25837b544", + "sha256:318c89edde72ff95d8df67d82aca03861240512994a597a435a1011ba18dbc7f", + "sha256:35d74ebdb3f71f112b36c2629cf32323adfbf42679e2751252acd468f5001c07", + "sha256:50e0a55ec74bf2d7a0ebf50ac580a209582c2dd0f7ab51bc270f1b4a0027454e", + "sha256:5dea00b62d28654b71ca92463656d80646675628d0828e08a5f3b57e12869e13", + "sha256:60c521e21031632aa0d87ca5ba0c1c05f3daacadb34c093585a0be6780f698e4", + "sha256:6515e878f91894c2e4340d81f0911857998ccaf04dbc1bba781e3d89cbf70608", + "sha256:6d2ff3c984b8a569bc1383cd468fc06b70d7b59d5c2854ca39f1436ae8394117", + "sha256:71667eb2ccca4c3537d9414b1bc00554cb7f91527c17ee4ec38027201f8f1603", + "sha256:717157e61b3a71d3d26ad4e1770dc85156c9af435659a25ee6407dc866cb258d", + "sha256:71f7a8c6b124e904db550f5b9fe483d28b896d4135e45c4ea381ad3b8a0e3256", + "sha256:936bba394682049919dda062d33435b3be211dc3dcaa011e09634f060ec878b2", + "sha256:a1733b8e84e7e40a9853e505fe68cc54339f97273bdfe6f3ed980095f769ddc7", + "sha256:a2c1590b90aa7bd741b54c62b78de05d4186271e34e2377e0289d943b3522273", + "sha256:a7e28d6396563955f7af437894a36bf2b279462239a41028323e04b85179058b", + "sha256:a8035ba590658bae7562786c9cc6ea1a84aa49d3afab157e414c9e2ea74f496d", + "sha256:a8cdb91dddb04436bd2f098b8fdf4b81352e68cf4d2c6756fcc414791076569b", + "sha256:ac60daa1dc83e8821eed155796b0f7888b6b916cf61d620a4ddd8200ac70cd64", + "sha256:af4860132c8c05261a5f5f8467f1b269bf1c7c23902d75f2be57c4a7f2394b3e", + "sha256:bc221ffbc2150458b1cd71cdd9ddd5bb37962b036e41b8be258280b5b01da1dd", + "sha256:ce55289d5659b5b12b3db4dc9b7075b70cef5631e56530f14b2945e8836f2d20", + "sha256:d9881356dc48e58910c53af82b57183879129fa30492be69058c5b0d9fddf391", + "sha256:dbcf59334ff645e6a67cd5f78b4b2cdb76384cdf587fa0d2dc85f634a72e1a3e", + "sha256:ebf577c7a6744e9e1bd3fee45fc74a02710b214f94e2bde344912d85e0c9af7c", + "sha256:f081c03f413f59390a80b3e351cc2b2ea0205839714dbc364519bcf51f4b56ca", + "sha256:fdbb46fad4fb47443b5b8ac76904b2e7a66556844f33370861b4788db0f8816a", + "sha256:fdcd28360dbb6203fb5219b1a5658df226ac9bebc2542a9e8f457de959d713d0" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==3.7.2" + }, + "mypy-extensions": { + "hashes": [ + "sha256:4392f6c0eb8a5668a69e23d168ffa70f0be9ccfd32b5cc2d26a34ae5b844552d", + "sha256:75dbf8955dc00442a438fc4d0666508a9a97b6bd41aa2f0ffe9d2f2725af0782" + ], + "markers": "python_version >= '3.5'", + "version": "==1.0.0" + }, "numba": { "hashes": [ "sha256:33c0500170d213e66d90558ad6aca57d3e03e97bb11da82e6d87ab793648cb17", @@ -75,47 +445,52 @@ "sha256:ff66d5b022af6c7d81ddbefa87768e78ed4f834ab2da6ca2fd0d60a9e69b94f5" ], "index": "pypi", + "markers": "python_version >= '3.8'", "version": "==0.57.1" }, "numpy": { "hashes": [ - "sha256:04640dab83f7c6c85abf9cd729c5b65f1ebd0ccf9de90b270cd61935eef0197f", - "sha256:1452241c290f3e2a312c137a9999cdbf63f78864d63c79039bda65ee86943f61", - "sha256:222e40d0e2548690405b0b3c7b21d1169117391c2e82c378467ef9ab4c8f0da7", - "sha256:2541312fbf09977f3b3ad449c4e5f4bb55d0dbf79226d7724211acc905049400", - "sha256:31f13e25b4e304632a4619d0e0777662c2ffea99fcae2029556b17d8ff958aef", - "sha256:4602244f345453db537be5314d3983dbf5834a9701b7723ec28923e2889e0bb2", - "sha256:4979217d7de511a8d57f4b4b5b2b965f707768440c17cb70fbf254c4b225238d", - "sha256:4c21decb6ea94057331e111a5bed9a79d335658c27ce2adb580fb4d54f2ad9bc", - "sha256:6620c0acd41dbcb368610bb2f4d83145674040025e5536954782467100aa8835", - "sha256:692f2e0f55794943c5bfff12b3f56f99af76f902fc47487bdfe97856de51a706", - "sha256:7215847ce88a85ce39baf9e89070cb860c98fdddacbaa6c0da3ffb31b3350bd5", - "sha256:79fc682a374c4a8ed08b331bef9c5f582585d1048fa6d80bc6c35bc384eee9b4", - "sha256:7ffe43c74893dbf38c2b0a1f5428760a1a9c98285553c89e12d70a96a7f3a4d6", - "sha256:80f5e3a4e498641401868df4208b74581206afbee7cf7b8329daae82676d9463", - "sha256:95f7ac6540e95bc440ad77f56e520da5bf877f87dca58bd095288dce8940532a", - "sha256:9667575fb6d13c95f1b36aca12c5ee3356bf001b714fc354eb5465ce1609e62f", - "sha256:a5425b114831d1e77e4b5d812b69d11d962e104095a5b9c3b641a218abcc050e", - "sha256:b4bea75e47d9586d31e892a7401f76e909712a0fd510f58f5337bea9572c571e", - "sha256:b7b1fc9864d7d39e28f41d089bfd6353cb5f27ecd9905348c24187a768c79694", - "sha256:befe2bf740fd8373cf56149a5c23a0f601e82869598d41f8e188a0e9869926f8", - "sha256:c0bfb52d2169d58c1cdb8cc1f16989101639b34c7d3ce60ed70b19c63eba0b64", - "sha256:d11efb4dbecbdf22508d55e48d9c8384db795e1b7b51ea735289ff96613ff74d", - "sha256:dd80e219fd4c71fc3699fc1dadac5dcf4fd882bfc6f7ec53d30fa197b8ee22dc", - "sha256:e2926dac25b313635e4d6cf4dc4e51c8c0ebfed60b801c799ffc4c32bf3d1254", - "sha256:e98f220aa76ca2a977fe435f5b04d7b3470c0a2e6312907b37ba6068f26787f2", - "sha256:ed094d4f0c177b1b8e7aa9cba7d6ceed51c0e569a5318ac0ca9a090680a6a1b1", - "sha256:f136bab9c2cfd8da131132c2cf6cc27331dd6fae65f95f69dcd4ae3c3639c810", - "sha256:f3a86ed21e4f87050382c7bc96571755193c4c1392490744ac73d660e8f564a9" + "sha256:0cfe07133fd00b27edee5e6385e333e9eeb010607e8a46e1cd673f05f8596595", + "sha256:11a1f3816ea82eed4178102c56281782690ab5993251fdfd75039aad4d20385f", + "sha256:2762331de395739c91f1abb88041f94a080cb1143aeec791b3b223976228af3f", + "sha256:283d9de87c0133ef98f93dfc09fad3fb382f2a15580de75c02b5bb36a5a159a5", + "sha256:3d22662b4b10112c545c91a0741f2436f8ca979ab3d69d03d19322aa970f9695", + "sha256:41388e32e40b41dd56eb37fcaa7488b2b47b0adf77c66154d6b89622c110dfe9", + "sha256:42c16cec1c8cf2728f1d539bd55aaa9d6bb48a7de2f41eb944697293ef65a559", + "sha256:47ee7a839f5885bc0c63a74aabb91f6f40d7d7b639253768c4199b37aede7982", + "sha256:5a311ee4d983c487a0ab546708edbdd759393a3dc9cd30305170149fedd23c88", + "sha256:5dc65644f75a4c2970f21394ad8bea1a844104f0fe01f278631be1c7eae27226", + "sha256:6ed0d073a9c54ac40c41a9c2d53fcc3d4d4ed607670b9e7b0de1ba13b4cbfe6f", + "sha256:76ba7c40e80f9dc815c5e896330700fd6e20814e69da9c1267d65a4d051080f1", + "sha256:818b9be7900e8dc23e013a92779135623476f44a0de58b40c32a15368c01d471", + "sha256:a024181d7aef0004d76fb3bce2a4c9f2e67a609a9e2a6ff2571d30e9976aa383", + "sha256:a955e4128ac36797aaffd49ab44ec74a71c11d6938df83b1285492d277db5397", + "sha256:a97a954a8c2f046d3817c2bce16e3c7e9a9c2afffaf0400f5c16df5172a67c9c", + "sha256:a97e82c39d9856fe7d4f9b86d8a1e66eff99cf3a8b7ba48202f659703d27c46f", + "sha256:b55b953a1bdb465f4dc181758570d321db4ac23005f90ffd2b434cc6609a63dd", + "sha256:bb02929b0d6bfab4c48a79bd805bd7419114606947ec8284476167415171f55b", + "sha256:bece0a4a49e60e472a6d1f70ac6cdea00f9ab80ff01132f96bd970cdd8a9e5a9", + "sha256:e41e8951749c4b5c9a2dc5fdbc1a4eec6ab2a140fdae9b460b0f557eed870f4d", + "sha256:f71d57cc8645f14816ae249407d309be250ad8de93ef61d9709b45a0ddf4050c" ], + "index": "pypi", "markers": "python_version >= '3.8'", - "version": "==1.24.4" + "version": "==1.22.0" + }, + "packaging": { + "hashes": [ + "sha256:994793af429502c4ea2ebf6bf664629d07c1a9fe974af92966e4b8d2df7edc61", + "sha256:a392980d2b6cffa644431898be54b0045151319d1e7ec34f0cfed48767dd334f" + ], + "markers": "python_version >= '3.7'", + "version": "==23.1" }, "pillow": { "hashes": [ "sha256:00e65f5e822decd501e374b0650146063fbb30a7264b4d2744bdd7b913e0cab5", "sha256:040586f7d37b34547153fa383f7f9aed68b738992380ac911447bb78f2abe530", "sha256:0b6eb5502f45a60a3f411c63187db83a3d3107887ad0d036c13ce836f8a36f1d", + "sha256:1ce91b6ec08d866b14413d3f0bbdea7e24dfdc8e59f562bb77bc3fe60b6144ca", "sha256:1f62406a884ae75fb2f818694469519fb685cc7eaff05d3451a9ebe55c646891", "sha256:22c10cc517668d44b211717fd9775799ccec4124b9a7f7b3635fc5386e584992", "sha256:3400aae60685b06bb96f99a21e1ada7bc7a413d5f49bce739828ecd9391bb8f7", @@ -145,6 +520,7 @@ "sha256:9fb218c8a12e51d7ead2a7c9e101a04982237d4855716af2e9499306728fb485", "sha256:a74ba0c356aaa3bb8e3eb79606a87669e7ec6444be352870623025d75a14a2bf", "sha256:b4f69b3700201b80bb82c3a97d5e9254084f6dd5fb5b16fc1a7b974260f89f43", + "sha256:bc2ec7c7b5d66b8ec9ce9f720dbb5fa4bace0f545acd34870eff4a369b44bf37", "sha256:c189af0545965fa8d3b9613cfdb0cd37f9d71349e0f7750e1fd704648d475ed2", "sha256:c1fbe7621c167ecaa38ad29643d77a9ce7311583761abf7836e1510c580bf3dd", "sha256:c7cf14a27b0d6adfaebb3ae4153f1e516df54e47e42dcc073d7b3d76111a8d86", @@ -169,81 +545,350 @@ "sha256:faaf07ea35355b01a35cb442dd950d8f1bb5b040a7787791a535de13db15ed90" ], "index": "pypi", + "markers": "python_version >= '3.8'", "version": "==10.0.0" }, + "pyglet": { + "hashes": [ + "sha256:8a8317fbb2bae145bd80f6d92d66b6dbbc9d13f1cbbed682ff55793a63003a46", + "sha256:e4cc8dc2f09d8487f7b3e2d93bd1961528afe989d058177b26a46d3508fd2c33" + ], + "index": "pypi", + "version": "==1.4.11" + }, + "pyopengl": { + "hashes": [ + "sha256:a6ab19cf290df6101aaf7470843a9c46207789855746399d0af92521a0a92b7a", + "sha256:eef31a3888e6984fd4d8e6c9961b184c9813ca82604d37fe3da80eb000a76c86" + ], + "index": "pypi", + "version": "==3.1.7" + }, + "pyparsing": { + "hashes": [ + "sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb", + "sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc" + ], + "markers": "python_full_version >= '3.6.8'", + "version": "==3.0.9" + }, + "python-dateutil": { + "hashes": [ + "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86", + "sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==2.8.2" + }, + "pyyaml": { + "hashes": [ + "sha256:062582fca9fabdd2c8b54a3ef1c978d786e0f6b3a1510e0ac93ef59e0ddae2bc", + "sha256:1635fd110e8d85d55237ab316b5b011de701ea0f29d07611174a1b42f1444741", + "sha256:184c5108a2aca3c5b3d3bf9395d50893a7ab82a38004c8f61c258d4428e80206", + "sha256:18aeb1bf9a78867dc38b259769503436b7c72f7a1f1f4c93ff9a17de54319b27", + "sha256:1d4c7e777c441b20e32f52bd377e0c409713e8bb1386e1099c2415f26e479595", + "sha256:1e2722cc9fbb45d9b87631ac70924c11d3a401b2d7f410cc0e3bbf249f2dca62", + "sha256:1fe35611261b29bd1de0070f0b2f47cb6ff71fa6595c077e42bd0c419fa27b98", + "sha256:28c119d996beec18c05208a8bd78cbe4007878c6dd15091efb73a30e90539696", + "sha256:42f8152b8dbc4fe7d96729ec2b99c7097d656dc1213a3229ca5383f973a5ed6d", + "sha256:4fb147e7a67ef577a588a0e2c17b6db51dda102c71de36f8549b6816a96e1867", + "sha256:50550eb667afee136e9a77d6dc71ae76a44df8b3e51e41b77f6de2932bfe0f47", + "sha256:510c9deebc5c0225e8c96813043e62b680ba2f9c50a08d3724c7f28a747d1486", + "sha256:5773183b6446b2c99bb77e77595dd486303b4faab2b086e7b17bc6bef28865f6", + "sha256:596106435fa6ad000c2991a98fa58eeb8656ef2325d7e158344fb33864ed87e3", + "sha256:6965a7bc3cf88e5a1c3bd2e0b5c22f8d677dc88a455344035f03399034eb3007", + "sha256:69b023b2b4daa7548bcfbd4aa3da05b3a74b772db9e23b982788168117739938", + "sha256:704219a11b772aea0d8ecd7058d0082713c3562b4e271b849ad7dc4a5c90c13c", + "sha256:7e07cbde391ba96ab58e532ff4803f79c4129397514e1413a7dc761ccd755735", + "sha256:81e0b275a9ecc9c0c0c07b4b90ba548307583c125f54d5b6946cfee6360c733d", + "sha256:9046c58c4395dff28dd494285c82ba00b546adfc7ef001486fbf0324bc174fba", + "sha256:9eb6caa9a297fc2c2fb8862bc5370d0303ddba53ba97e71f08023b6cd73d16a8", + "sha256:a0cd17c15d3bb3fa06978b4e8958dcdc6e0174ccea823003a106c7d4d7899ac5", + "sha256:afd7e57eddb1a54f0f1a974bc4391af8bcce0b444685d936840f125cf046d5bd", + "sha256:b1275ad35a5d18c62a7220633c913e1b42d44b46ee12554e5fd39c70a243d6a3", + "sha256:b786eecbdf8499b9ca1d697215862083bd6d2a99965554781d0d8d1ad31e13a0", + "sha256:ba336e390cd8e4d1739f42dfe9bb83a3cc2e80f567d8805e11b46f4a943f5515", + "sha256:baa90d3f661d43131ca170712d903e6295d1f7a0f595074f151c0aed377c9b9c", + "sha256:bc1bf2925a1ecd43da378f4db9e4f799775d6367bdb94671027b73b393a7c42c", + "sha256:bd4af7373a854424dabd882decdc5579653d7868b8fb26dc7d0e99f823aa5924", + "sha256:bf07ee2fef7014951eeb99f56f39c9bb4af143d8aa3c21b1677805985307da34", + "sha256:bfdf460b1736c775f2ba9f6a92bca30bc2095067b8a9d77876d1fad6cc3b4a43", + "sha256:c8098ddcc2a85b61647b2590f825f3db38891662cfc2fc776415143f599bb859", + "sha256:d2b04aac4d386b172d5b9692e2d2da8de7bfb6c387fa4f801fbf6fb2e6ba4673", + "sha256:d858aa552c999bc8a8d57426ed01e40bef403cd8ccdd0fc5f6f04a00414cac2a", + "sha256:f003ed9ad21d6a4713f0a9b5a7a0a79e08dd0f221aff4525a2be4c346ee60aab", + "sha256:f22ac1c3cac4dbc50079e965eba2c1058622631e526bd9afd45fedd49ba781fa", + "sha256:faca3bdcf85b2fc05d06ff3fbc1f83e1391b3e724afa3feba7d13eeab355484c", + "sha256:fca0e3a251908a499833aa292323f32437106001d436eca0e6e7833256674585", + "sha256:fd1592b3fdf65fff2ad0004b5e363300ef59ced41c2e6b3a99d4089fa8c5435d", + "sha256:fd66fc5d0da6d9815ba2cebeb4205f95818ff4b79c3ebe268e75d961704af52f" + ], + "index": "pypi", + "markers": "python_version >= '3.6'", + "version": "==6.0.1" + }, + "requests": { + "hashes": [ + "sha256:58cd2187c01e70e6e26505bca751777aa9f2ee0b7f4300988b709f44e013003f", + "sha256:942c5a758f98d790eaed1a29cb6eefc7ffb0d1cf7af05c3d2791656dbd6ad1e1" + ], + "index": "pypi", + "markers": "python_version >= '3.7'", + "version": "==2.31.0" + }, "scipy": { "hashes": [ - "sha256:08d957ca82d3535b3b9ba6c8ff355d78fe975271874e2af267cb5add5bd78625", - "sha256:249cfa465c379c9bb2c20123001e151ff5e29b351cbb7f9c91587260602c58d0", - "sha256:366a6a937110d80dca4f63b3f5b00cc89d36f678b2d124a01067b154e692bab1", - "sha256:39154437654260a52871dfde852adf1b93b1d1bc5dc0ffa70068f16ec0be2624", - "sha256:396fae3f8c12ad14c5f3eb40499fd06a6fef8393a6baa352a652ecd51e74e029", - "sha256:3b9963798df1d8a52db41a6fc0e6fa65b1c60e85d73da27ae8bb754de4792481", - "sha256:3e8eb42db36526b130dfbc417609498a6192381abc1975b91e3eb238e0b41c1a", - "sha256:512fdc18c65f76dadaca139348e525646d440220d8d05f6d21965b8d4466bccd", - "sha256:aec8c62fbe52914f9cf28d846cf0401dd80ab80788bbab909434eb336ed07c04", - "sha256:b41a0f322b4eb51b078cb3441e950ad661ede490c3aca66edef66f4b37ab1877", - "sha256:b4bb943010203465ac81efa392e4645265077b4d9e99b66cf3ed33ae12254173", - "sha256:b588311875c58d1acd4ef17c983b9f1ab5391755a47c3d70b6bd503a45bfaf71", - "sha256:ba94eeef3c9caa4cea7b402a35bb02a5714ee1ee77eb98aca1eed4543beb0f4c", - "sha256:be8c962a821957fdde8c4044efdab7a140c13294997a407eaee777acf63cbf0c", - "sha256:cce154372f0ebe88556ed06d7b196e9c2e0c13080ecb58d0f35062dc7cc28b47", - "sha256:d51565560565a0307ed06fa0ec4c6f21ff094947d4844d6068ed04400c72d0c3", - "sha256:e866514bc2d660608447b6ba95c8900d591f2865c07cca0aa4f7ff3c4ca70f30", - "sha256:fb5b492fa035334fd249f0973cc79ecad8b09c604b42a127a677b45a9a3d4289", - "sha256:ffb28e3fa31b9c376d0fb1f74c1f13911c8c154a760312fbee87a21eb21efe31" + "sha256:0f3261f14b767b316d7137c66cc4f33a80ea05841b9c87ad83a726205b901423", + "sha256:10eb6af2f751aa3424762948e5352f707b0dece77288206f227864ddf675aca0", + "sha256:1342ca385c673208f32472830c10110a9dcd053cf0c4b7d4cd7026d0335a6c1d", + "sha256:214cdf04bbae7a54784f8431f976704ed607c4bc69ba0d5d5d6a9df84374df76", + "sha256:2b997a5369e2d30c97995dcb29d638701f8000d04df01b8e947f206e5d0ac788", + "sha256:2c91cf049ffb5575917f2a01da1da082fd24ed48120d08a6e7297dfcac771dcd", + "sha256:3aeb87661de987f8ec56fa6950863994cd427209158255a389fc5aea51fa7055", + "sha256:4447ad057d7597476f9862ecbd9285bbf13ba9d73ce25acfa4e4b11c6801b4c9", + "sha256:542a757e2a6ec409e71df3d8fd20127afbbacb1c07990cb23c5870c13953d899", + "sha256:8d9886f44ef8c9e776cb7527fb01455bf4f4a46c455c4682edc2c2cc8cd78562", + "sha256:90d3b1364e751d8214e325c371f0ee0dd38419268bf4888b2ae1040a6b266b2a", + "sha256:95763fbda1206bec41157582bea482f50eb3702c85fffcf6d24394b071c0e87a", + "sha256:ac74b1512d38718fb6a491c439aa7b3605b96b1ed3be6599c17d49d6c60fca18", + "sha256:afdb0d983f6135d50770dd979df50bf1c7f58b5b33e0eb8cf5c73c70600eae1d", + "sha256:b0620240ef445b5ddde52460e6bc3483b7c9c750275369379e5f609a1050911c", + "sha256:b133f237bd8ba73bad51bc12eb4f2d84cbec999753bf25ba58235e9fc2096d80", + "sha256:b29318a5e39bd200ca4381d80b065cdf3076c7d7281c5e36569e99273867f61d", + "sha256:b8425fa963a32936c9773ee3ce44a765d8ff67eed5f4ac81dc1e4a819a238ee9", + "sha256:d2b813bfbe8dec6a75164523de650bad41f4405d35b0fa24c2c28ae07fcefb20", + "sha256:d690e1ca993c8f7ede6d22e5637541217fc6a4d3f78b3672a6fe454dbb7eb9a7", + "sha256:e367904a0fec76433bf3fbf3e85bf60dae8e9e585ffd21898ab1085a29a04d16", + "sha256:ea932570b1c2a30edafca922345854ff2cd20d43cd9123b6dacfdecebfc1a80b", + "sha256:f28f1f6cfeb48339c192efc6275749b2a25a7e49c4d8369a28b6591da02fbc9a", + "sha256:f73102f769ee06041a3aa26b5841359b1a93cc364ce45609657751795e8f4a4a", + "sha256:fa4909c6c20c3d91480533cddbc0e7c6d849e7d9ded692918c76ce5964997898" ], "index": "pypi", - "version": "==1.11.1" + "markers": "python_version < '3.13' and python_version >= '3.9'", + "version": "==1.11.2" + }, + "six": { + "hashes": [ + "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926", + "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==1.16.0" + }, + "typing-extensions": { + "hashes": [ + "sha256:440d5dd3af93b060174bf433bccd69b0babc3b15b1a8dca43789fd7f61514b36", + "sha256:b75ddc264f0ba5615db7ba217daeb99701ad295353c45f9e95963337ceeeffb2" + ], + "markers": "python_version >= '3.7'", + "version": "==4.7.1" + }, + "typing-inspect": { + "hashes": [ + "sha256:9ee6fc59062311ef8547596ab6b955e1b8aa46242d854bfc78f4f6b0eff35f9f", + "sha256:b23fc42ff6f6ef6954e4852c1fb512cdd18dbea03134f91f856a95ccc9461f78" + ], + "version": "==0.9.0" + }, + "urllib3": { + "hashes": [ + "sha256:8d22f86aae8ef5e410d4f539fde9ce6b2113a001bb4d189e0aed70642d602b11", + "sha256:de7df1803967d2c2a98e4b11bb7d6bd9210474c46e8a0401514e3a42a75ebde4" + ], + "markers": "python_version >= '3.7'", + "version": "==2.0.4" + }, + "yamldataclassconfig": { + "hashes": [ + "sha256:5b06a5ced890f2e18ec2a42b8e57d6659f2134554eb8402319b22c5993a5725f", + "sha256:dbbaa499875b9187b1446279440aa3e8e1dc1d5878fe46a27272b0d4b70b85a4" + ], + "index": "pypi", + "markers": "python_version >= '3.7'", + "version": "==1.5.0" } }, "develop": { + "asttokens": { + "hashes": [ + "sha256:4622110b2a6f30b77e1473affaa97e711bc2f07d3f10848420ff1898edbe94f3", + "sha256:6b0ac9e93fb0335014d382b8fa9b3afa7df546984258005da0b9e7095b3deb1c" + ], + "version": "==2.2.1" + }, + "backcall": { + "hashes": [ + "sha256:5cbdbf27be5e7cfadb448baf0aa95508f91f2bbc6c6437cd9cd06e2a4c215e1e", + "sha256:fbbce6a29f263178a1f7915c1940bde0ec2b2a967566fe1c65c1dfb7422bd255" + ], + "version": "==0.2.0" + }, "black": { "hashes": [ - "sha256:064101748afa12ad2291c2b91c960be28b817c0c7eaa35bec09cc63aa56493c5", - "sha256:0945e13506be58bf7db93ee5853243eb368ace1c08a24c65ce108986eac65915", - "sha256:11c410f71b876f961d1de77b9699ad19f939094c3a677323f43d7a29855fe326", - "sha256:1c7b8d606e728a41ea1ccbd7264677e494e87cf630e399262ced92d4a8dac940", - "sha256:1d06691f1eb8de91cd1b322f21e3bfc9efe0c7ca1f0e1eb1db44ea367dff656b", - "sha256:3238f2aacf827d18d26db07524e44741233ae09a584273aa059066d644ca7b30", - "sha256:32daa9783106c28815d05b724238e30718f34155653d4d6e125dc7daec8e260c", - "sha256:35d1381d7a22cc5b2be2f72c7dfdae4072a3336060635718cc7e1ede24221d6c", - "sha256:3a150542a204124ed00683f0db1f5cf1c2aaaa9cc3495b7a3b5976fb136090ab", - "sha256:48f9d345675bb7fbc3dd85821b12487e1b9a75242028adad0333ce36ed2a6d27", - "sha256:50cb33cac881766a5cd9913e10ff75b1e8eb71babf4c7104f2e9c52da1fb7de2", - "sha256:562bd3a70495facf56814293149e51aa1be9931567474993c7942ff7d3533961", - "sha256:67de8d0c209eb5b330cce2469503de11bca4085880d62f1628bd9972cc3366b9", - "sha256:6b39abdfb402002b8a7d030ccc85cf5afff64ee90fa4c5aebc531e3ad0175ddb", - "sha256:6f3c333ea1dd6771b2d3777482429864f8e258899f6ff05826c3a4fcc5ce3f70", - "sha256:714290490c18fb0126baa0fca0a54ee795f7502b44177e1ce7624ba1c00f2331", - "sha256:7c3eb7cea23904399866c55826b31c1f55bbcd3890ce22ff70466b907b6775c2", - "sha256:92c543f6854c28a3c7f39f4d9b7694f9a6eb9d3c5e2ece488c327b6e7ea9b266", - "sha256:a6f6886c9869d4daae2d1715ce34a19bbc4b95006d20ed785ca00fa03cba312d", - "sha256:a8a968125d0a6a404842fa1bf0b349a568634f856aa08ffaff40ae0dfa52e7c6", - "sha256:c7ab5790333c448903c4b721b59c0d80b11fe5e9803d8703e84dcb8da56fec1b", - "sha256:e114420bf26b90d4b9daa597351337762b63039752bdf72bf361364c1aa05925", - "sha256:e198cf27888ad6f4ff331ca1c48ffc038848ea9f031a3b40ba36aced7e22f2c8", - "sha256:ec751418022185b0c1bb7d7736e6933d40bbb14c14a0abcf9123d1b159f98dd4", - "sha256:f0bd2f4a58d6666500542b26354978218a9babcdc972722f4bf90779524515f3" + "sha256:01ede61aac8c154b55f35301fac3e730baf0c9cf8120f65a9cd61a81cfb4a0c3", + "sha256:022a582720b0d9480ed82576c920a8c1dde97cc38ff11d8d8859b3bd6ca9eedb", + "sha256:25cc308838fe71f7065df53aedd20327969d05671bac95b38fdf37ebe70ac087", + "sha256:27eb7a0c71604d5de083757fbdb245b1a4fae60e9596514c6ec497eb63f95320", + "sha256:327a8c2550ddc573b51e2c352adb88143464bb9d92c10416feb86b0f5aee5ff6", + "sha256:47e56d83aad53ca140da0af87678fb38e44fd6bc0af71eebab2d1f59b1acf1d3", + "sha256:501387a9edcb75d7ae8a4412bb8749900386eaef258f1aefab18adddea1936bc", + "sha256:552513d5cd5694590d7ef6f46e1767a4df9af168d449ff767b13b084c020e63f", + "sha256:5c4bc552ab52f6c1c506ccae05681fab58c3f72d59ae6e6639e8885e94fe2587", + "sha256:642496b675095d423f9b8448243336f8ec71c9d4d57ec17bf795b67f08132a91", + "sha256:6d1c6022b86f83b632d06f2b02774134def5d4d4f1dac8bef16d90cda18ba28a", + "sha256:7f3bf2dec7d541b4619b8ce526bda74a6b0bffc480a163fed32eb8b3c9aed8ad", + "sha256:831d8f54c3a8c8cf55f64d0422ee875eecac26f5f649fb6c1df65316b67c8926", + "sha256:8417dbd2f57b5701492cd46edcecc4f9208dc75529bcf76c514864e48da867d9", + "sha256:86cee259349b4448adb4ef9b204bb4467aae74a386bce85d56ba4f5dc0da27be", + "sha256:893695a76b140881531062d48476ebe4a48f5d1e9388177e175d76234ca247cd", + "sha256:9fd59d418c60c0348505f2ddf9609c1e1de8e7493eab96198fc89d9f865e7a96", + "sha256:ad0014efc7acf0bd745792bd0d8857413652979200ab924fbf239062adc12491", + "sha256:b5b0ee6d96b345a8b420100b7d71ebfdd19fab5e8301aff48ec270042cd40ac2", + "sha256:c333286dc3ddca6fdff74670b911cccedacb4ef0a60b34e491b8a67c833b343a", + "sha256:f9062af71c59c004cd519e2fb8f5d25d39e46d3af011b41ab43b9c74e27e236f", + "sha256:fb074d8b213749fa1d077d630db0d5f8cc3b2ae63587ad4116e8a436e9bbe995" ], "index": "pypi", - "version": "==23.3.0" + "markers": "python_version >= '3.8'", + "version": "==23.7.0" }, "click": { "hashes": [ - "sha256:2739815aaa5d2c986a88f1e9230c55e17f0caad3d958a5e13ad0797c166db9e3", - "sha256:b97d0c74955da062a7d4ef92fadb583806a585b2ea81958a81bd72726cbb8e37" + "sha256:ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28", + "sha256:ca9853ad459e787e2192211578cc907e7594e294c7ccc834310722b41b9ca6de" + ], + "markers": "python_version >= '3.7'", + "version": "==8.1.7" + }, + "colorama": { + "hashes": [ + "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44", + "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6" + ], + "markers": "sys_platform == 'win32'", + "version": "==0.4.6" + }, + "comm": { + "hashes": [ + "sha256:354e40a59c9dd6db50c5cc6b4acc887d82e9603787f83b68c01a80a923984d15", + "sha256:6d52794cba11b36ed9860999cd10fd02d6b2eac177068fdd585e1e2f8a96e67a" + ], + "markers": "python_version >= '3.6'", + "version": "==0.1.4" + }, + "debugpy": { + "hashes": [ + "sha256:038c51268367c9c935905a90b1c2d2dbfe304037c27ba9d19fe7409f8cdc710c", + "sha256:1093a5c541af079c13ac8c70ab8b24d1d35c8cacb676306cf11e57f699c02926", + "sha256:3370ef1b9951d15799ef7af41f8174194f3482ee689988379763ef61a5456426", + "sha256:38651c3639a4e8bbf0ca7e52d799f6abd07d622a193c406be375da4d510d968d", + "sha256:3de5d0f97c425dc49bce4293df6a04494309eedadd2b52c22e58d95107e178d9", + "sha256:4b9eba71c290852f959d2cf8a03af28afd3ca639ad374d393d53d367f7f685b2", + "sha256:65b28435a17cba4c09e739621173ff90c515f7b9e8ea469b92e3c28ef8e5cdfb", + "sha256:72f5d2ecead8125cf669e62784ef1e6300f4067b0f14d9f95ee00ae06fc7c4f7", + "sha256:85969d864c45f70c3996067cfa76a319bae749b04171f2cdeceebe4add316155", + "sha256:890f7ab9a683886a0f185786ffbda3b46495c4b929dab083b8c79d6825832a52", + "sha256:903bd61d5eb433b6c25b48eae5e23821d4c1a19e25c9610205f5aeaccae64e32", + "sha256:92b6dae8bfbd497c90596bbb69089acf7954164aea3228a99d7e43e5267f5b36", + "sha256:973a97ed3b434eab0f792719a484566c35328196540676685c975651266fccf9", + "sha256:d16882030860081e7dd5aa619f30dec3c2f9a421e69861125f83cc372c94e57d", + "sha256:d4ac7a4dba28801d184b7fc0e024da2635ca87d8b0a825c6087bb5168e3c0d28", + "sha256:eea8d8cfb9965ac41b99a61f8e755a8f50e9a20330938ad8271530210f54e09c", + "sha256:f0851403030f3975d6e2eaa4abf73232ab90b98f041e3c09ba33be2beda43fcf", + "sha256:fe87ec0182ef624855d05e6ed7e0b7cb1359d2ffa2a925f8ec2d22e98b75d0ca" ], "markers": "python_version >= '3.7'", - "version": "==8.1.4" + "version": "==1.6.7.post1" + }, + "decorator": { + "hashes": [ + "sha256:637996211036b6385ef91435e4fae22989472f9d571faba8927ba8253acbc330", + "sha256:b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186" + ], + "markers": "python_version >= '3.5'", + "version": "==5.1.1" + }, + "exceptiongroup": { + "hashes": [ + "sha256:097acd85d473d75af5bb98e41b61ff7fe35efe6675e4f9370ec6ec5126d160e9", + "sha256:343280667a4585d195ca1cf9cef84a4e178c4b6cf2274caef9859782b567d5e3" + ], + "markers": "python_version < '3.11'", + "version": "==1.1.3" + }, + "executing": { + "hashes": [ + "sha256:0314a69e37426e3608aada02473b4161d4caf5a4b244d1d0c48072b8fee7bacc", + "sha256:19da64c18d2d851112f09c287f8d3dbbdf725ab0e569077efb6cdcbd3497c107" + ], + "version": "==1.2.0" }, "flake8": { "hashes": [ - "sha256:3833794e27ff64ea4e9cf5d410082a8b97ff1a06c16aa3d2027339cd0f1195c7", - "sha256:c61007e76655af75e6785a931f452915b371dc48f56efd765247c8fe68f2b181" + "sha256:d5b3857f07c030bdb5bf41c7f53799571d75c4491748a3adcd47de929e34cd23", + "sha256:ffdfce58ea94c6580c77888a86506937f9a1a227dfcd15f245d694ae20a6b6e5" ], "index": "pypi", - "version": "==6.0.0" + "markers": "python_full_version >= '3.8.1'", + "version": "==6.1.0" + }, + "iniconfig": { + "hashes": [ + "sha256:2d91e135bf72d31a410b17c16da610a82cb55f6b0477d1a902134b24a455b8b3", + "sha256:b6a85871a79d2e3b22d2d1b94ac2824226a63c6b741c88f7ae975f18b6778374" + ], + "markers": "python_version >= '3.7'", + "version": "==2.0.0" + }, + "ipykernel": { + "hashes": [ + "sha256:050391364c0977e768e354bdb60cbbfbee7cbb943b1af1618382021136ffd42f", + "sha256:c8a2430b357073b37c76c21c52184db42f6b4b0e438e1eb7df3c4440d120497c" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==6.25.1" + }, + "ipython": { + "hashes": [ + "sha256:1d197b907b6ba441b692c48cf2a3a2de280dc0ac91a3405b39349a50272ca0a1", + "sha256:248aca623f5c99a6635bc3857677b7320b9b8039f99f070ee0d20a5ca5a8e6bf" + ], + "markers": "python_version >= '3.9'", + "version": "==8.14.0" + }, + "jedi": { + "hashes": [ + "sha256:bcf9894f1753969cbac8022a8c2eaee06bfa3724e4192470aaffe7eb6272b0c4", + "sha256:cb8ce23fbccff0025e9386b5cf85e892f94c9b822378f8da49970471335ac64e" + ], + "markers": "python_version >= '3.6'", + "version": "==0.19.0" + }, + "jupyter-client": { + "hashes": [ + "sha256:3af69921fe99617be1670399a0b857ad67275eefcfa291e2c81a160b7b650f5f", + "sha256:7441af0c0672edc5d28035e92ba5e32fadcfa8a4e608a434c228836a89df6158" + ], + "markers": "python_version >= '3.8'", + "version": "==8.3.0" + }, + "jupyter-core": { + "hashes": [ + "sha256:5ba5c7938a7f97a6b0481463f7ff0dbac7c15ba48cf46fa4035ca6e838aa1aba", + "sha256:ae9036db959a71ec1cac33081eeb040a79e681f08ab68b0883e9a676c7a90dce" + ], + "markers": "python_version >= '3.8'", + "version": "==5.3.1" + }, + "matplotlib-inline": { + "hashes": [ + "sha256:f1f41aab5328aa5aaea9b16d083b128102f8712542f819fe7e6a420ff581b311", + "sha256:f887e5f10ba98e8d2b150ddcf4702c1e5f8b3a20005eb0f74bfdbd360ee6f304" + ], + "markers": "python_version >= '3.5'", + "version": "==0.1.6" }, "mccabe": { "hashes": [ @@ -261,6 +906,14 @@ "markers": "python_version >= '3.5'", "version": "==1.0.0" }, + "nest-asyncio": { + "hashes": [ + "sha256:5301c82941b550b3123a1ea772ba9a1c80bad3a182be8c1a5ae6ad3be57a9657", + "sha256:6a80f7b98f24d9083ed24608977c09dd608d83f91cccc24c9d2cba6d10e01c10" + ], + "markers": "python_version >= '3.5'", + "version": "==1.5.7" + }, "packaging": { "hashes": [ "sha256:994793af429502c4ea2ebf6bf664629d07c1a9fe974af92966e4b8d2df7edc61", @@ -269,37 +922,254 @@ "markers": "python_version >= '3.7'", "version": "==23.1" }, + "parso": { + "hashes": [ + "sha256:8c07be290bb59f03588915921e29e8a50002acaf2cdc5fa0e0114f91709fafa0", + "sha256:c001d4636cd3aecdaf33cbb40aebb59b094be2a74c556778ef5576c175e19e75" + ], + "markers": "python_version >= '3.6'", + "version": "==0.8.3" + }, "pathspec": { "hashes": [ - "sha256:2798de800fa92780e33acca925945e9a19a133b715067cf165b8866c15a31687", - "sha256:d8af70af76652554bd134c22b3e8a1cc46ed7d91edcdd721ef1a0c51a84a5293" + "sha256:1d6ed233af05e679efb96b1851550ea95bbb64b7c490b0f5aa52996c11e92a20", + "sha256:e0d8d0ac2f12da61956eb2306b69f9469b42f4deb0f3cb6ed47b9cce9996ced3" ], "markers": "python_version >= '3.7'", - "version": "==0.11.1" + "version": "==0.11.2" + }, + "pickleshare": { + "hashes": [ + "sha256:87683d47965c1da65cdacaf31c8441d12b8044cdec9aca500cd78fc2c683afca", + "sha256:9649af414d74d4df115d5d718f82acb59c9d418196b7b4290ed47a12ce62df56" + ], + "version": "==0.7.5" }, "platformdirs": { "hashes": [ - "sha256:b0cabcb11063d21a0b261d557acb0a9d2126350e63b70cdf7db6347baea456dc", - "sha256:ca9ed98ce73076ba72e092b23d3c93ea6c4e186b3f1c3dad6edd98ff6ffcca2e" + "sha256:b45696dab2d7cc691a3226759c0d3b00c47c8b6e293d96f6436f733303f77f6d", + "sha256:d7c24979f292f916dc9cbf8648319032f551ea8c49a4c9bf2fb556a02070ec1d" ], "markers": "python_version >= '3.7'", - "version": "==3.8.0" + "version": "==3.10.0" + }, + "pluggy": { + "hashes": [ + "sha256:c2fd55a7d7a3863cba1a013e4e2414658b1d07b6bc57b3919e0c63c9abb99849", + "sha256:d12f0c4b579b15f5e054301bb226ee85eeeba08ffec228092f8defbaa3a4c4b3" + ], + "markers": "python_version >= '3.7'", + "version": "==1.2.0" + }, + "prompt-toolkit": { + "hashes": [ + "sha256:04505ade687dc26dc4284b1ad19a83be2f2afe83e7a828ace0c72f3a1df72aac", + "sha256:9dffbe1d8acf91e3de75f3b544e4842382fc06c6babe903ac9acb74dc6e08d88" + ], + "markers": "python_full_version >= '3.7.0'", + "version": "==3.0.39" + }, + "psutil": { + "hashes": [ + "sha256:104a5cc0e31baa2bcf67900be36acde157756b9c44017b86b2c049f11957887d", + "sha256:3c6f686f4225553615612f6d9bc21f1c0e305f75d7d8454f9b46e901778e7217", + "sha256:4aef137f3345082a3d3232187aeb4ac4ef959ba3d7c10c33dd73763fbc063da4", + "sha256:5410638e4df39c54d957fc51ce03048acd8e6d60abc0f5107af51e5fb566eb3c", + "sha256:5b9b8cb93f507e8dbaf22af6a2fd0ccbe8244bf30b1baad6b3954e935157ae3f", + "sha256:7a7dd9997128a0d928ed4fb2c2d57e5102bb6089027939f3b722f3a210f9a8da", + "sha256:89518112647f1276b03ca97b65cc7f64ca587b1eb0278383017c2a0dcc26cbe4", + "sha256:8c5f7c5a052d1d567db4ddd231a9d27a74e8e4a9c3f44b1032762bd7b9fdcd42", + "sha256:ab8ed1a1d77c95453db1ae00a3f9c50227ebd955437bcf2a574ba8adbf6a74d5", + "sha256:acf2aef9391710afded549ff602b5887d7a2349831ae4c26be7c807c0a39fac4", + "sha256:b258c0c1c9d145a1d5ceffab1134441c4c5113b2417fafff7315a917a026c3c9", + "sha256:be8929ce4313f9f8146caad4272f6abb8bf99fc6cf59344a3167ecd74f4f203f", + "sha256:c607bb3b57dc779d55e1554846352b4e358c10fff3abf3514a7a6601beebdb30", + "sha256:ea8518d152174e1249c4f2a1c89e3e6065941df2fa13a1ab45327716a23c2b48" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==5.9.5" + }, + "pure-eval": { + "hashes": [ + "sha256:01eaab343580944bc56080ebe0a674b39ec44a945e6d09ba7db3cb8cec289350", + "sha256:2b45320af6dfaa1750f543d714b6d1c520a1688dec6fd24d339063ce0aaa9ac3" + ], + "version": "==0.2.2" }, "pycodestyle": { "hashes": [ - "sha256:347187bdb476329d98f695c213d7295a846d1152ff4fe9bacb8a9590b8ee7053", - "sha256:8a4eaf0d0495c7395bdab3589ac2db602797d76207242c17d470186815706610" + "sha256:259bcc17857d8a8b3b4a2327324b79e5f020a13c16074670f9c8c8f872ea76d0", + "sha256:5d1013ba8dc7895b548be5afb05740ca82454fd899971563d2ef625d090326f8" ], - "markers": "python_version >= '3.6'", - "version": "==2.10.0" + "markers": "python_version >= '3.8'", + "version": "==2.11.0" }, "pyflakes": { "hashes": [ - "sha256:ec55bf7fe21fff7f1ad2f7da62363d749e2a470500eab1b555334b67aa1ef8cf", - "sha256:ec8b276a6b60bd80defed25add7e439881c19e64850afd9b346283d4165fd0fd" + "sha256:4132f6d49cb4dae6819e5379898f2b8cce3c5f23994194c24b77d5da2e36f774", + "sha256:a0aae034c444db0071aa077972ba4768d40c830d9539fd45bf4cd3f8f6992efc" + ], + "markers": "python_version >= '3.8'", + "version": "==3.1.0" + }, + "pygments": { + "hashes": [ + "sha256:13fc09fa63bc8d8671a6d247e1eb303c4b343eaee81d861f3404db2935653692", + "sha256:1daff0494820c69bc8941e407aa20f577374ee88364ee10a98fdbe0aece96e29" + ], + "markers": "python_version >= '3.7'", + "version": "==2.16.1" + }, + "pytest": { + "hashes": [ + "sha256:78bf16451a2eb8c7a2ea98e32dc119fd2aa758f1d5d66dbf0a59d69a3969df32", + "sha256:b4bf8c45bd59934ed84001ad51e11b4ee40d40a1229d2c79f9c592b0a3f6bd8a" + ], + "index": "pypi", + "markers": "python_version >= '3.7'", + "version": "==7.4.0" + }, + "python-dateutil": { + "hashes": [ + "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86", + "sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==2.8.2" + }, + "pywin32": { + "hashes": [ + "sha256:06d3420a5155ba65f0b72f2699b5bacf3109f36acbe8923765c22938a69dfc8d", + "sha256:1c73ea9a0d2283d889001998059f5eaaba3b6238f767c9cf2833b13e6a685f65", + "sha256:37257794c1ad39ee9be652da0462dc2e394c8159dfd913a8a4e8eb6fd346da0e", + "sha256:383229d515657f4e3ed1343da8be101000562bf514591ff383ae940cad65458b", + "sha256:39b61c15272833b5c329a2989999dcae836b1eed650252ab1b7bfbe1d59f30f4", + "sha256:5821ec52f6d321aa59e2db7e0a35b997de60c201943557d108af9d4ae1ec7040", + "sha256:70dba0c913d19f942a2db25217d9a1b726c278f483a919f1abfed79c9cf64d3a", + "sha256:72c5f621542d7bdd4fdb716227be0dd3f8565c11b280be6315b06ace35487d36", + "sha256:84f4471dbca1887ea3803d8848a1616429ac94a4a8d05f4bc9c5dcfd42ca99c8", + "sha256:a7639f51c184c0272e93f244eb24dafca9b1855707d94c192d4a0b4c01e1100e", + "sha256:e25fd5b485b55ac9c057f67d94bc203f3f6595078d1fb3b458c9c28b7153a802", + "sha256:e4c092e2589b5cf0d365849e73e02c391c1349958c5ac3e9d5ccb9a28e017b3a", + "sha256:e65028133d15b64d2ed8f06dd9fbc268352478d4f9289e69c190ecd6818b6407", + "sha256:e8ac1ae3601bee6ca9f7cb4b5363bf1c0badb935ef243c4733ff9a393b1690c0" + ], + "markers": "sys_platform == 'win32' and platform_python_implementation != 'PyPy'", + "version": "==306" + }, + "pyzmq": { + "hashes": [ + "sha256:019e59ef5c5256a2c7378f2fb8560fc2a9ff1d315755204295b2eab96b254d0a", + "sha256:034239843541ef7a1aee0c7b2cb7f6aafffb005ede965ae9cbd49d5ff4ff73cf", + "sha256:03b3f49b57264909aacd0741892f2aecf2f51fb053e7d8ac6767f6c700832f45", + "sha256:047a640f5c9c6ade7b1cc6680a0e28c9dd5a0825135acbd3569cc96ea00b2505", + "sha256:04ccbed567171579ec2cebb9c8a3e30801723c575601f9a990ab25bcac6b51e2", + "sha256:057e824b2aae50accc0f9a0570998adc021b372478a921506fddd6c02e60308e", + "sha256:11baebdd5fc5b475d484195e49bae2dc64b94a5208f7c89954e9e354fc609d8f", + "sha256:11c1d2aed9079c6b0c9550a7257a836b4a637feb334904610f06d70eb44c56d2", + "sha256:11d58723d44d6ed4dd677c5615b2ffb19d5c426636345567d6af82be4dff8a55", + "sha256:12720a53e61c3b99d87262294e2b375c915fea93c31fc2336898c26d7aed34cd", + "sha256:17ef5f01d25b67ca8f98120d5fa1d21efe9611604e8eb03a5147360f517dd1e2", + "sha256:18d43df3f2302d836f2a56f17e5663e398416e9dd74b205b179065e61f1a6edf", + "sha256:1a5d26fe8f32f137e784f768143728438877d69a586ddeaad898558dc971a5ae", + "sha256:1af379b33ef33757224da93e9da62e6471cf4a66d10078cf32bae8127d3d0d4a", + "sha256:1ccf825981640b8c34ae54231b7ed00271822ea1c6d8ba1090ebd4943759abf5", + "sha256:21eb4e609a154a57c520e3d5bfa0d97e49b6872ea057b7c85257b11e78068222", + "sha256:2243700cc5548cff20963f0ca92d3e5e436394375ab8a354bbea2b12911b20b0", + "sha256:255ca2b219f9e5a3a9ef3081512e1358bd4760ce77828e1028b818ff5610b87b", + "sha256:259c22485b71abacdfa8bf79720cd7bcf4b9d128b30ea554f01ae71fdbfdaa23", + "sha256:25f0e6b78220aba09815cd1f3a32b9c7cb3e02cb846d1cfc526b6595f6046618", + "sha256:273bc3959bcbff3f48606b28229b4721716598d76b5aaea2b4a9d0ab454ec062", + "sha256:292fe3fc5ad4a75bc8df0dfaee7d0babe8b1f4ceb596437213821f761b4589f9", + "sha256:2ca57a5be0389f2a65e6d3bb2962a971688cbdd30b4c0bd188c99e39c234f414", + "sha256:2d163a18819277e49911f7461567bda923461c50b19d169a062536fffe7cd9d2", + "sha256:2d81f1ddae3858b8299d1da72dd7d19dd36aab654c19671aa8a7e7fb02f6638a", + "sha256:2f957ce63d13c28730f7fd6b72333814221c84ca2421298f66e5143f81c9f91f", + "sha256:330f9e188d0d89080cde66dc7470f57d1926ff2fb5576227f14d5be7ab30b9fa", + "sha256:34c850ce7976d19ebe7b9d4b9bb8c9dfc7aac336c0958e2651b88cbd46682123", + "sha256:35b5ab8c28978fbbb86ea54958cd89f5176ce747c1fb3d87356cf698048a7790", + "sha256:3669cf8ee3520c2f13b2e0351c41fea919852b220988d2049249db10046a7afb", + "sha256:381469297409c5adf9a0e884c5eb5186ed33137badcbbb0560b86e910a2f1e76", + "sha256:3d0a409d3b28607cc427aa5c30a6f1e4452cc44e311f843e05edb28ab5e36da0", + "sha256:44e58a0554b21fc662f2712814a746635ed668d0fbc98b7cb9d74cb798d202e6", + "sha256:458dea649f2f02a0b244ae6aef8dc29325a2810aa26b07af8374dc2a9faf57e3", + "sha256:48e466162a24daf86f6b5ca72444d2bf39a5e58da5f96370078be67c67adc978", + "sha256:49d238cf4b69652257db66d0c623cd3e09b5d2e9576b56bc067a396133a00d4a", + "sha256:4ca1ed0bb2d850aa8471387882247c68f1e62a4af0ce9c8a1dbe0d2bf69e41fb", + "sha256:52533489f28d62eb1258a965f2aba28a82aa747202c8fa5a1c7a43b5db0e85c1", + "sha256:548d6482dc8aadbe7e79d1b5806585c8120bafa1ef841167bc9090522b610fa6", + "sha256:5619f3f5a4db5dbb572b095ea3cb5cc035335159d9da950830c9c4db2fbb6995", + "sha256:57459b68e5cd85b0be8184382cefd91959cafe79ae019e6b1ae6e2ba8a12cda7", + "sha256:5a34d2395073ef862b4032343cf0c32a712f3ab49d7ec4f42c9661e0294d106f", + "sha256:61706a6b6c24bdece85ff177fec393545a3191eeda35b07aaa1458a027ad1304", + "sha256:724c292bb26365659fc434e9567b3f1adbdb5e8d640c936ed901f49e03e5d32e", + "sha256:73461eed88a88c866656e08f89299720a38cb4e9d34ae6bf5df6f71102570f2e", + "sha256:76705c9325d72a81155bb6ab48d4312e0032bf045fb0754889133200f7a0d849", + "sha256:76c1c8efb3ca3a1818b837aea423ff8a07bbf7aafe9f2f6582b61a0458b1a329", + "sha256:77a41c26205d2353a4c94d02be51d6cbdf63c06fbc1295ea57dad7e2d3381b71", + "sha256:79986f3b4af059777111409ee517da24a529bdbd46da578b33f25580adcff728", + "sha256:7cff25c5b315e63b07a36f0c2bab32c58eafbe57d0dce61b614ef4c76058c115", + "sha256:7f7e58effd14b641c5e4dec8c7dab02fb67a13df90329e61c869b9cc607ef752", + "sha256:820c4a08195a681252f46926de10e29b6bbf3e17b30037bd4250d72dd3ddaab8", + "sha256:87e34f31ca8f168c56d6fbf99692cc8d3b445abb5bfd08c229ae992d7547a92a", + "sha256:8f03d3f0d01cb5a018debeb412441996a517b11c5c17ab2001aa0597c6d6882c", + "sha256:90f26dc6d5f241ba358bef79be9ce06de58d477ca8485e3291675436d3827cf8", + "sha256:955215ed0604dac5b01907424dfa28b40f2b2292d6493445dd34d0dfa72586a8", + "sha256:985bbb1316192b98f32e25e7b9958088431d853ac63aca1d2c236f40afb17c83", + "sha256:a382372898a07479bd34bda781008e4a954ed8750f17891e794521c3e21c2e1c", + "sha256:a882ac0a351288dd18ecae3326b8a49d10c61a68b01419f3a0b9a306190baf69", + "sha256:aa8d6cdc8b8aa19ceb319aaa2b660cdaccc533ec477eeb1309e2a291eaacc43a", + "sha256:abc719161780932c4e11aaebb203be3d6acc6b38d2f26c0f523b5b59d2fc1996", + "sha256:abf34e43c531bbb510ae7e8f5b2b1f2a8ab93219510e2b287a944432fad135f3", + "sha256:ade6d25bb29c4555d718ac6d1443a7386595528c33d6b133b258f65f963bb0f6", + "sha256:afea96f64efa98df4da6958bae37f1cbea7932c35878b185e5982821bc883369", + "sha256:b1579413ae492b05de5a6174574f8c44c2b9b122a42015c5292afa4be2507f28", + "sha256:b3451108ab861040754fa5208bca4a5496c65875710f76789a9ad27c801a0075", + "sha256:b9af3757495c1ee3b5c4e945c1df7be95562277c6e5bccc20a39aec50f826cd0", + "sha256:bc16ac425cc927d0a57d242589f87ee093884ea4804c05a13834d07c20db203c", + "sha256:c2910967e6ab16bf6fbeb1f771c89a7050947221ae12a5b0b60f3bca2ee19bca", + "sha256:c2b92812bd214018e50b6380ea3ac0c8bb01ac07fcc14c5f86a5bb25e74026e9", + "sha256:c2f20ce161ebdb0091a10c9ca0372e023ce24980d0e1f810f519da6f79c60800", + "sha256:c56d748ea50215abef7030c72b60dd723ed5b5c7e65e7bc2504e77843631c1a6", + "sha256:c7c133e93b405eb0d36fa430c94185bdd13c36204a8635470cccc200723c13bb", + "sha256:c9c6c9b2c2f80747a98f34ef491c4d7b1a8d4853937bb1492774992a120f475d", + "sha256:cbc8df5c6a88ba5ae385d8930da02201165408dde8d8322072e3e5ddd4f68e22", + "sha256:cff084c6933680d1f8b2f3b4ff5bbb88538a4aac00d199ac13f49d0698727ecb", + "sha256:d2045d6d9439a0078f2a34b57c7b18c4a6aef0bee37f22e4ec9f32456c852c71", + "sha256:d20a0ddb3e989e8807d83225a27e5c2eb2260eaa851532086e9e0fa0d5287d83", + "sha256:d457aed310f2670f59cc5b57dcfced452aeeed77f9da2b9763616bd57e4dbaae", + "sha256:d89528b4943d27029a2818f847c10c2cecc79fa9590f3cb1860459a5be7933eb", + "sha256:db0b2af416ba735c6304c47f75d348f498b92952f5e3e8bff449336d2728795d", + "sha256:deee9ca4727f53464daf089536e68b13e6104e84a37820a88b0a057b97bba2d2", + "sha256:df27ffddff4190667d40de7beba4a950b5ce78fe28a7dcc41d6f8a700a80a3c0", + "sha256:e0c95ddd4f6e9fca4e9e3afaa4f9df8552f0ba5d1004e89ef0a68e1f1f9807c7", + "sha256:e1c1be77bc5fb77d923850f82e55a928f8638f64a61f00ff18a67c7404faf008", + "sha256:e1ffa1c924e8c72778b9ccd386a7067cddf626884fd8277f503c48bb5f51c762", + "sha256:e2400a94f7dd9cb20cd012951a0cbf8249e3d554c63a9c0cdfd5cbb6c01d2dec", + "sha256:e61f091c3ba0c3578411ef505992d356a812fb200643eab27f4f70eed34a29ef", + "sha256:e8a701123029cc240cea61dd2d16ad57cab4691804143ce80ecd9286b464d180", + "sha256:eadbefd5e92ef8a345f0525b5cfd01cf4e4cc651a2cffb8f23c0dd184975d787", + "sha256:f32260e556a983bc5c7ed588d04c942c9a8f9c2e99213fec11a031e316874c7e", + "sha256:f8115e303280ba09f3898194791a153862cbf9eef722ad8f7f741987ee2a97c7", + "sha256:fedbdc753827cf014c01dbbee9c3be17e5a208dcd1bf8641ce2cd29580d1f0d4" ], "markers": "python_version >= '3.6'", - "version": "==3.0.1" + "version": "==25.1.1" + }, + "six": { + "hashes": [ + "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926", + "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==1.16.0" + }, + "stack-data": { + "hashes": [ + "sha256:32d2dd0376772d01b6cb9fc996f3c8b57a357089dec328ed4b6553d037eaf815", + "sha256:cbb2a53eb64e5785878201a97ed7c7b94883f48b87bfb0bbe8b623c74679e4a8" + ], + "version": "==0.6.2" }, "tomli": { "hashes": [ @@ -308,6 +1178,38 @@ ], "markers": "python_version < '3.11'", "version": "==2.0.1" + }, + "tornado": { + "hashes": [ + "sha256:1bd19ca6c16882e4d37368e0152f99c099bad93e0950ce55e71daed74045908f", + "sha256:22d3c2fa10b5793da13c807e6fc38ff49a4f6e1e3868b0a6f4164768bb8e20f5", + "sha256:502fba735c84450974fec147340016ad928d29f1e91f49be168c0a4c18181e1d", + "sha256:65ceca9500383fbdf33a98c0087cb975b2ef3bfb874cb35b8de8740cf7f41bd3", + "sha256:71a8db65160a3c55d61839b7302a9a400074c9c753040455494e2af74e2501f2", + "sha256:7ac51f42808cca9b3613f51ffe2a965c8525cb1b00b7b2d56828b8045354f76a", + "sha256:7d01abc57ea0dbb51ddfed477dfe22719d376119844e33c661d873bf9c0e4a16", + "sha256:805d507b1f588320c26f7f097108eb4023bbaa984d63176d1652e184ba24270a", + "sha256:9dc4444c0defcd3929d5c1eb5706cbe1b116e762ff3e0deca8b715d14bf6ec17", + "sha256:ceb917a50cd35882b57600709dd5421a418c29ddc852da8bcdab1f0db33406b0", + "sha256:e7d8db41c0181c80d76c982aacc442c0783a2c54d6400fe028954201a2e032fe" + ], + "markers": "python_version >= '3.8'", + "version": "==6.3.3" + }, + "traitlets": { + "hashes": [ + "sha256:9e6ec080259b9a5940c797d58b613b5e31441c2257b87c2e795c5228ae80d2d8", + "sha256:f6cde21a9c68cf756af02035f72d5a723bf607e862e7be33ece505abf4a3bad9" + ], + "markers": "python_version >= '3.7'", + "version": "==5.9.0" + }, + "wcwidth": { + "hashes": [ + "sha256:795b138f6875577cd91bba52baf9e445cd5118fd32723b460e30a0af30ea230e", + "sha256:a5220780a404dbe3353789870978e472cfe477761f06ee55077256e509b156d0" + ], + "version": "==0.2.6" } } } diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 00000000..0f2dd6a3 --- /dev/null +++ b/requirements.txt @@ -0,0 +1,34 @@ +-i https://pypi.org/simple +certifi==2023.7.22; python_version >= '3.6' +charset-normalizer==3.2.0; python_full_version >= '3.7.0' +cloudpickle==2.2.1; python_version >= '3.6' +contourpy==1.1.0; python_version >= '3.8' +cycler==0.11.0; python_version >= '3.6' +dataclasses-json==0.5.14; python_version < '3.13' and python_version >= '3.7' +-e . +farama-notifications==0.0.4 +fonttools==4.42.1; python_version >= '3.8' +future==0.18.3; python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3' +gymnasium==0.29.1; python_version >= '3.8' +idna==3.4; python_version >= '3.5' +kiwisolver==1.4.4; python_version >= '3.7' +llvmlite==0.40.1; python_version >= '3.8' +marshmallow==3.20.1; python_version >= '3.8' +matplotlib==3.7.2; python_version >= '3.8' +mypy-extensions==1.0.0; python_version >= '3.5' +numba==0.57.1; python_version >= '3.8' +numpy==1.22.0; python_version >= '3.8' +packaging==23.1; python_version >= '3.7' +pillow==10.0.0; python_version >= '3.8' +pyglet==1.4.11 +pyopengl==3.1.7 +pyparsing==3.0.9; python_full_version >= '3.6.8' +python-dateutil==2.8.2; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' +pyyaml==6.0.1; python_version >= '3.6' +requests==2.31.0; python_version >= '3.7' +scipy==1.11.2; python_version < '3.13' and python_version >= '3.9' +six==1.16.0; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' +typing-extensions==4.7.1; python_version >= '3.7' +typing-inspect==0.9.0 +urllib3==2.0.4; python_version >= '3.7' +yamldataclassconfig==1.5.0; python_version >= '3.7' diff --git a/setup.py b/setup.py index 85b33204..c51abdaf 100644 --- a/setup.py +++ b/setup.py @@ -9,7 +9,7 @@ package_dir={"": "gym"}, install_requires=[ "gymnasium", - "numpy<=1.22.0,>=1.18.0", + "numpy<=1.25.0,>=1.18.0", "Pillow>=9.0.1", "scipy>=1.7.3", "numba>=0.55.2", From 3bfc1d9ff13ace00d8a079c370f15ba64ae67167 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Tue, 22 Aug 2023 19:34:35 -0400 Subject: [PATCH 13/32] Deleted duplicated tests --- gym/f110_gym/envs/collision_models.py | 86 --------------------------- 1 file changed, 86 deletions(-) diff --git a/gym/f110_gym/envs/collision_models.py b/gym/f110_gym/envs/collision_models.py index 8961cdc8..87547ab6 100644 --- a/gym/f110_gym/envs/collision_models.py +++ b/gym/f110_gym/envs/collision_models.py @@ -271,89 +271,3 @@ def get_vertices(pose, length, width): [[rl[0], rl[1]], [rr[0], rr[1]], [fr[0], fr[1]], [fl[0], fl[1]]] ) return vertices - - -""" -Unit test for GJK collision checks -Author: Hongrui Zheng -""" - -import time -import unittest - - -class CollisionTests(unittest.TestCase): - def setUp(self): - # test params - np.random.seed(1234) - - # Collision check body - self.vertices1 = np.asarray([[4, 11.0], [5, 5], [9, 9], [10, 10]]) - - # car size - self.length = 0.32 - self.width = 0.22 - - def test_get_vert(self): - test_pose = np.array([2.3, 6.7, 0.8]) - vertices = get_vertices(test_pose, self.length, self.width) - rect = np.vstack((vertices, vertices[0, :])) - import matplotlib.pyplot as plt - - plt.scatter(test_pose[0], test_pose[1], c="red") - plt.plot(rect[:, 0], rect[:, 1]) - plt.xlim([1, 4]) - plt.ylim([5, 8]) - plt.axes().set_aspect("equal") - plt.show() - self.assertTrue(vertices.shape == (4, 2)) - - def test_get_vert_fps(self): - test_pose = np.array([2.3, 6.7, 0.8]) - start = time.time() - for _ in range(1000): - vertices = get_vertices(test_pose, self.length, self.width) - elapsed = time.time() - start - fps = 1000 / elapsed - print("get vertices fps:", fps) - self.assertTrue(fps > 500) - - def test_random_collision(self): - # perturb the body by a small amount and make sure it all collides with the original body - for _ in range(1000): - a = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - b = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - self.assertTrue(collision(a, b)) - - def test_multiple_collisions(self): - a = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - b = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - c = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - d = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - e = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - f = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - g = self.vertices1 + 10.0 - allv = np.stack((a, b, c, d, e, f, g)) - collisions, collision_idx = collision_multiple(allv) - self.assertTrue( - np.all(collisions == np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.0])) - ) - self.assertTrue( - np.all(collision_idx == np.array([5.0, 5.0, 5.0, 5.0, 5.0, 4.0, -1.0])) - ) - - def test_fps(self): - # also perturb the body but mainly want to test GJK speed - start = time.time() - for _ in range(1000): - a = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - b = self.vertices1 + np.random.normal(size=(self.vertices1.shape)) / 100.0 - collision(a, b) - elapsed = time.time() - start - fps = 1000 / elapsed - print("gjk fps:", fps) - self.assertTrue(fps > 500) - - -if __name__ == "__main__": - unittest.main() From cac50b978e94a1c5619ea102e8cde6c347a357f3 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Tue, 22 Aug 2023 19:57:50 -0400 Subject: [PATCH 14/32] Updated for linting. --- Pipfile | 2 + Pipfile.lock | 72 +++++++++----- docs/conf.py | 69 ++++++------- examples/random_trackgen.py | 4 +- examples/waypoint_follow.py | 5 +- gym/f110_gym/envs/__init__.py | 6 -- gym/f110_gym/envs/action.py | 2 +- gym/f110_gym/envs/base_classes.py | 3 +- gym/f110_gym/envs/cubic_spline.py | 3 +- gym/f110_gym/envs/dynamic_models.py | 141 +++++++++++++++++++++++++-- gym/f110_gym/envs/f110_env.py | 28 ++---- gym/f110_gym/envs/f110_env_backup.py | 34 +++---- gym/f110_gym/envs/laser_models.py | 11 +-- gym/f110_gym/envs/rendering.py | 13 +-- gym/f110_gym/envs/track.py | 1 - gym/f110_gym/envs/utils.py | 4 +- pytest.ini | 6 -- setup.cfg | 16 +++ tests/legacy_scan_gen.py | 1 + tests/pyglet_test_.py | 12 +-- tests/test_collision_checks.py | 1 + tests/test_dynamics.py | 5 +- tests/test_f110_env.py | 8 +- tests/test_observation.py | 14 +-- tests/test_scan_sim.py | 15 ++- tests/test_track.py | 3 +- tests/test_utils.py | 1 - 27 files changed, 287 insertions(+), 193 deletions(-) delete mode 100644 pytest.ini create mode 100644 setup.cfg diff --git a/Pipfile b/Pipfile index ff334207..a191989d 100644 --- a/Pipfile +++ b/Pipfile @@ -22,6 +22,8 @@ flake8 = "*" black = "*" ipykernel = "*" pytest = "*" +isort = "*" +autoflake = "*" [requires] python_version = "3.10" diff --git a/Pipfile.lock b/Pipfile.lock index 2f6fa17a..4a2c7255 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "cd0dd1f62d1aec40708cf8248298c17e0522dcdf12d80f78c2bc9e2a64f236f5" + "sha256": "cf830ecdf81a7befa15768216c25db2cb59af898f4cf869fe4e59f3dd569a008" }, "pipfile-spec": 6, "requires": { @@ -450,32 +450,38 @@ }, "numpy": { "hashes": [ - "sha256:0cfe07133fd00b27edee5e6385e333e9eeb010607e8a46e1cd673f05f8596595", - "sha256:11a1f3816ea82eed4178102c56281782690ab5993251fdfd75039aad4d20385f", - "sha256:2762331de395739c91f1abb88041f94a080cb1143aeec791b3b223976228af3f", - "sha256:283d9de87c0133ef98f93dfc09fad3fb382f2a15580de75c02b5bb36a5a159a5", - "sha256:3d22662b4b10112c545c91a0741f2436f8ca979ab3d69d03d19322aa970f9695", - "sha256:41388e32e40b41dd56eb37fcaa7488b2b47b0adf77c66154d6b89622c110dfe9", - "sha256:42c16cec1c8cf2728f1d539bd55aaa9d6bb48a7de2f41eb944697293ef65a559", - "sha256:47ee7a839f5885bc0c63a74aabb91f6f40d7d7b639253768c4199b37aede7982", - "sha256:5a311ee4d983c487a0ab546708edbdd759393a3dc9cd30305170149fedd23c88", - "sha256:5dc65644f75a4c2970f21394ad8bea1a844104f0fe01f278631be1c7eae27226", - "sha256:6ed0d073a9c54ac40c41a9c2d53fcc3d4d4ed607670b9e7b0de1ba13b4cbfe6f", - "sha256:76ba7c40e80f9dc815c5e896330700fd6e20814e69da9c1267d65a4d051080f1", - "sha256:818b9be7900e8dc23e013a92779135623476f44a0de58b40c32a15368c01d471", - "sha256:a024181d7aef0004d76fb3bce2a4c9f2e67a609a9e2a6ff2571d30e9976aa383", - "sha256:a955e4128ac36797aaffd49ab44ec74a71c11d6938df83b1285492d277db5397", - "sha256:a97a954a8c2f046d3817c2bce16e3c7e9a9c2afffaf0400f5c16df5172a67c9c", - "sha256:a97e82c39d9856fe7d4f9b86d8a1e66eff99cf3a8b7ba48202f659703d27c46f", - "sha256:b55b953a1bdb465f4dc181758570d321db4ac23005f90ffd2b434cc6609a63dd", - "sha256:bb02929b0d6bfab4c48a79bd805bd7419114606947ec8284476167415171f55b", - "sha256:bece0a4a49e60e472a6d1f70ac6cdea00f9ab80ff01132f96bd970cdd8a9e5a9", - "sha256:e41e8951749c4b5c9a2dc5fdbc1a4eec6ab2a140fdae9b460b0f557eed870f4d", - "sha256:f71d57cc8645f14816ae249407d309be250ad8de93ef61d9709b45a0ddf4050c" + "sha256:04640dab83f7c6c85abf9cd729c5b65f1ebd0ccf9de90b270cd61935eef0197f", + "sha256:1452241c290f3e2a312c137a9999cdbf63f78864d63c79039bda65ee86943f61", + "sha256:222e40d0e2548690405b0b3c7b21d1169117391c2e82c378467ef9ab4c8f0da7", + "sha256:2541312fbf09977f3b3ad449c4e5f4bb55d0dbf79226d7724211acc905049400", + "sha256:31f13e25b4e304632a4619d0e0777662c2ffea99fcae2029556b17d8ff958aef", + "sha256:4602244f345453db537be5314d3983dbf5834a9701b7723ec28923e2889e0bb2", + "sha256:4979217d7de511a8d57f4b4b5b2b965f707768440c17cb70fbf254c4b225238d", + "sha256:4c21decb6ea94057331e111a5bed9a79d335658c27ce2adb580fb4d54f2ad9bc", + "sha256:6620c0acd41dbcb368610bb2f4d83145674040025e5536954782467100aa8835", + "sha256:692f2e0f55794943c5bfff12b3f56f99af76f902fc47487bdfe97856de51a706", + "sha256:7215847ce88a85ce39baf9e89070cb860c98fdddacbaa6c0da3ffb31b3350bd5", + "sha256:79fc682a374c4a8ed08b331bef9c5f582585d1048fa6d80bc6c35bc384eee9b4", + "sha256:7ffe43c74893dbf38c2b0a1f5428760a1a9c98285553c89e12d70a96a7f3a4d6", + "sha256:80f5e3a4e498641401868df4208b74581206afbee7cf7b8329daae82676d9463", + "sha256:95f7ac6540e95bc440ad77f56e520da5bf877f87dca58bd095288dce8940532a", + "sha256:9667575fb6d13c95f1b36aca12c5ee3356bf001b714fc354eb5465ce1609e62f", + "sha256:a5425b114831d1e77e4b5d812b69d11d962e104095a5b9c3b641a218abcc050e", + "sha256:b4bea75e47d9586d31e892a7401f76e909712a0fd510f58f5337bea9572c571e", + "sha256:b7b1fc9864d7d39e28f41d089bfd6353cb5f27ecd9905348c24187a768c79694", + "sha256:befe2bf740fd8373cf56149a5c23a0f601e82869598d41f8e188a0e9869926f8", + "sha256:c0bfb52d2169d58c1cdb8cc1f16989101639b34c7d3ce60ed70b19c63eba0b64", + "sha256:d11efb4dbecbdf22508d55e48d9c8384db795e1b7b51ea735289ff96613ff74d", + "sha256:dd80e219fd4c71fc3699fc1dadac5dcf4fd882bfc6f7ec53d30fa197b8ee22dc", + "sha256:e2926dac25b313635e4d6cf4dc4e51c8c0ebfed60b801c799ffc4c32bf3d1254", + "sha256:e98f220aa76ca2a977fe435f5b04d7b3470c0a2e6312907b37ba6068f26787f2", + "sha256:ed094d4f0c177b1b8e7aa9cba7d6ceed51c0e569a5318ac0ca9a090680a6a1b1", + "sha256:f136bab9c2cfd8da131132c2cf6cc27331dd6fae65f95f69dcd4ae3c3639c810", + "sha256:f3a86ed21e4f87050382c7bc96571755193c4c1392490744ac73d660e8f564a9" ], "index": "pypi", "markers": "python_version >= '3.8'", - "version": "==1.22.0" + "version": "==1.24.4" }, "packaging": { "hashes": [ @@ -717,6 +723,15 @@ ], "version": "==2.2.1" }, + "autoflake": { + "hashes": [ + "sha256:62e1f74a0fdad898a96fee6f99fe8241af90ad99c7110c884b35855778412251", + "sha256:de409b009a34c1c2a7cc2aae84c4c05047f9773594317c6a6968bd497600d4a0" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==2.2.0" + }, "backcall": { "hashes": [ "sha256:5cbdbf27be5e7cfadb448baf0aa95508f91f2bbc6c6437cd9cd06e2a4c215e1e", @@ -858,6 +873,15 @@ "markers": "python_version >= '3.9'", "version": "==8.14.0" }, + "isort": { + "hashes": [ + "sha256:8bef7dde241278824a6d83f44a544709b065191b95b6e50894bdc722fcba0504", + "sha256:f84c2818376e66cf843d497486ea8fed8700b340f308f076c6fb1229dff318b6" + ], + "index": "pypi", + "markers": "python_full_version >= '3.8.0'", + "version": "==5.12.0" + }, "jedi": { "hashes": [ "sha256:bcf9894f1753969cbac8022a8c2eaee06bfa3724e4192470aaffe7eb6272b0c4", diff --git a/docs/conf.py b/docs/conf.py index 0e049f02..9362d15b 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,23 +1,23 @@ import os -import sys + import sphinx_rtd_theme -source_suffix = '.rst' -source_encoding = 'utf-8-sig' +source_suffix = ".rst" +source_encoding = "utf-8-sig" # -- Language ---------------------------------------------------------------- -env_tags = os.getenv('SPHINX_TAGS') +env_tags = os.getenv("SPHINX_TAGS") if env_tags != None: - for tag in env_tags.split(','): - print('Adding Sphinx tag: %s' % tag.strip()) + for tag in env_tags.split(","): + print("Adding Sphinx tag: %s" % tag.strip()) tags.add(tag.strip()) -language = os.getenv('READTHEDOCS_LANGUAGE', 'en') -is_i18n = tags.has('i18n') +language = os.getenv("READTHEDOCS_LANGUAGE", "en") +is_i18n = tags.has("i18n") # -- Theme ------------------------------------------------------------------- -on_rtd = os.environ.get('READTHEDOCS', None) == 'True' -html_theme = 'sphinx_rtd_theme' +on_rtd = os.environ.get("READTHEDOCS", None) == "True" +html_theme = "sphinx_rtd_theme" html_theme_path = [sphinx_rtd_theme.get_html_theme_path()] if on_rtd: using_rtd_theme = True @@ -25,40 +25,36 @@ # 'typekit_id': 'hiw1hhg', # 'analytics_id': '', # 'sticky_navigation': True # Set to False to disable the sticky nav while scrolling. - 'logo_only': False, # if we have a html_logo below, this shows /only/ the logo with no title text - 'collapse_navigation': False, # Collapse navigation (False makes it tree-like) - 'prev_next_buttons_location': 'bottom', + "logo_only": False, # if we have a html_logo below, this shows /only/ the logo with no title text + "collapse_navigation": False, # Collapse navigation (False makes it tree-like) + "prev_next_buttons_location": "bottom", # 'display_version': True, # Display the docs version # 'navigation_depth': 4, # Depth of the headers shown in the navigation bar } html_context = { - "display_github": not is_i18n, # Integrate GitHub - "github_user": "f1tenth", # Username - "github_repo": "f1tenth_gym", # Repo name - "github_version": "exp_py", # Version - "conf_py_path": "/docs/", # Path in the checkout to the docs root + "display_github": not is_i18n, # Integrate GitHub + "github_user": "f1tenth", # Username + "github_repo": "f1tenth_gym", # Repo name + "github_version": "exp_py", # Version + "conf_py_path": "/docs/", # Path in the checkout to the docs root } -html_favicon = 'assets/f1_stickers_02.png' +html_favicon = "assets/f1_stickers_02.png" -html_css_files = [ - 'css/custom.css' -] +html_css_files = ["css/custom.css"] -html_js_files = [ - 'css/custom.js' -] -html_logo = 'assets/f1tenth_gym.svg' +html_js_files = ["css/custom.js"] +html_logo = "assets/f1tenth_gym.svg" # -- Project information ----------------------------------------------------- -project = 'f1tenth_gym' +project = "f1tenth_gym" copyright = "2021, Hongrui Zheng, Matthew O'Kelly, Aman Sinha" -author = 'Hongrui Zheng' +author = "Hongrui Zheng" # The full version, including alpha/beta/rc tags -release = 'latest' -version = 'latest' +release = "latest" +version = "latest" # -- General configuration --------------------------------------------------- @@ -66,23 +62,20 @@ # Add any Sphinx extension module names here, as strings. They can be # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom # ones. -extensions = [ "breathe", "sphinx_rtd_theme", "sphinx.ext.autosectionlabel" -] +extensions = ["breathe", "sphinx_rtd_theme", "sphinx.ext.autosectionlabel"] # Breathe configuration -breathe_projects = { - "f1tenth_gym":"./xml" - } +breathe_projects = {"f1tenth_gym": "./xml"} # Add any paths that contain templates here, relative to this directory. -templates_path = ['_templates'] +templates_path = ["_templates"] # List of patterns, relative to source directory, that match files and # directories to ignore when looking for source files. # This pattern also affects html_static_path and html_extra_path. -exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] +exclude_patterns = ["_build", "Thumbs.db", ".DS_Store"] # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, # so a file named "default.css" will overwrite the builtin "default.css". -html_static_path = ['_static'] \ No newline at end of file +html_static_path = ["_static"] diff --git a/examples/random_trackgen.py b/examples/random_trackgen.py index 2130e9c4..51eff46a 100644 --- a/examples/random_trackgen.py +++ b/examples/random_trackgen.py @@ -30,13 +30,13 @@ - shapely - opencv-python """ +import math import pathlib import cv2 -import math +import matplotlib.pyplot as plt import numpy as np import shapely.geometry as shp -import matplotlib.pyplot as plt def main(args): diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index 5a0ffcea..12bfa0ad 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -1,11 +1,8 @@ import time -import yaml + import gymnasium as gym import numpy as np -from argparse import Namespace - from numba import njit - from pyglet.gl import GL_POINTS """ diff --git a/gym/f110_gym/envs/__init__.py b/gym/f110_gym/envs/__init__.py index 1cf17c53..e69de29b 100644 --- a/gym/f110_gym/envs/__init__.py +++ b/gym/f110_gym/envs/__init__.py @@ -1,6 +0,0 @@ -from f110_gym.envs.integrator import * -from f110_gym.envs.dynamic_models import * -from f110_gym.envs.f110_env import F110Env -from f110_gym.envs.laser_models import * -from f110_gym.envs.base_classes import * -from f110_gym.envs.collision_models import * diff --git a/gym/f110_gym/envs/action.py b/gym/f110_gym/envs/action.py index a4372f3b..cc779fa5 100644 --- a/gym/f110_gym/envs/action.py +++ b/gym/f110_gym/envs/action.py @@ -1,6 +1,6 @@ from abc import abstractmethod from enum import Enum -from typing import Any, Tuple, Dict +from typing import Any, Dict, Tuple import gymnasium as gym import numpy as np diff --git a/gym/f110_gym/envs/base_classes.py b/gym/f110_gym/envs/base_classes.py index b2156d1d..a75afd0b 100644 --- a/gym/f110_gym/envs/base_classes.py +++ b/gym/f110_gym/envs/base_classes.py @@ -27,12 +27,11 @@ Author: Hongrui Zheng """ import numpy as np - from f110_gym.envs import DynamicModel from f110_gym.envs.action import CarAction +from f110_gym.envs.collision_models import collision_multiple, get_vertices from f110_gym.envs.integrator import EulerIntegrator, IntegratorType from f110_gym.envs.laser_models import ScanSimulator2D, check_ttc_jit, ray_cast -from f110_gym.envs.collision_models import get_vertices, collision_multiple class RaceCar(object): diff --git a/gym/f110_gym/envs/cubic_spline.py b/gym/f110_gym/envs/cubic_spline.py index 925b4d4d..8b1a0fab 100644 --- a/gym/f110_gym/envs/cubic_spline.py +++ b/gym/f110_gym/envs/cubic_spline.py @@ -2,9 +2,10 @@ Code from Cubic spline planner Author: Atsushi Sakai(@Atsushi_twi) """ +import bisect import math + import numpy as np -import bisect class CubicSpline1D: diff --git a/gym/f110_gym/envs/dynamic_models.py b/gym/f110_gym/envs/dynamic_models.py index bc0618e0..0ca1af3d 100644 --- a/gym/f110_gym/envs/dynamic_models.py +++ b/gym/f110_gym/envs/dynamic_models.py @@ -109,8 +109,11 @@ def accl_constraints(vel, accl, v_switch, a_max, v_min, v_max): return accl + @njit(cache=True) -def steering_constraint(steering_angle, steering_velocity, s_min, s_max, sv_min, sv_max): +def steering_constraint( + steering_angle, steering_velocity, s_min, s_max, sv_min, sv_max +): """ Steering constraints, adjusts the steering velocity based on constraints @@ -140,7 +143,26 @@ def steering_constraint(steering_angle, steering_velocity, s_min, s_max, sv_min, @njit(cache=True) -def vehicle_dynamics_ks(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): +def vehicle_dynamics_ks( + x, + u_init, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): """ Single Track Kinematic Vehicle Dynamics. @@ -244,8 +266,28 @@ def vehicle_dynamics_ks_cog( ) return f + @njit(cache=True) -def vehicle_dynamics_st(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): +def vehicle_dynamics_st( + x, + u_init, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): """ Single Track Dynamic Vehicle Dynamics. @@ -371,6 +413,7 @@ def vehicle_dynamics_st(x, u_init, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max return f + @njit(cache=True) def pid(speed, steer, current_speed, current_steer, max_sv, max_a, max_v, min_v): """ @@ -416,14 +459,94 @@ def pid(speed, steer, current_speed, current_steer, max_sv, max_a, max_v, min_v) return accl, sv -def func_KS(x, t, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): - f = vehicle_dynamics_ks(x, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max) + +def func_KS( + x, + t, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): + f = vehicle_dynamics_ks( + x, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, + ) return f -def func_ST(x, t, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max): - f = vehicle_dynamics_st(x, u, mu, C_Sf, C_Sr, lf, lr, h, m, I, s_min, s_max, sv_min, sv_max, v_switch, a_max, v_min, v_max) + +def func_ST( + x, + t, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): + f = vehicle_dynamics_st( + x, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, + ) return f -if __name__ == '__main__': - unittest.main() \ No newline at end of file +if __name__ == "__main__": + unittest.main() diff --git a/gym/f110_gym/envs/f110_env.py b/gym/f110_gym/envs/f110_env.py index ce5c933e..d5cfd8ac 100644 --- a/gym/f110_gym/envs/f110_env.py +++ b/gym/f110_gym/envs/f110_env.py @@ -24,31 +24,24 @@ Author: Hongrui Zheng """ +import time + # gym imports import gymnasium as gym - -from f110_gym.envs import IntegratorType -from f110_gym.envs.action import CarActionEnum, from_single_to_multi_action_space - -from f110_gym.envs.track import Track - -# base classes -from f110_gym.envs.base_classes import Simulator, DynamicModel -from f110_gym.envs.observation import observation_factory - -from f110_gym.envs.utils import deep_update - - # others import numpy as np -import os -import time - # gl import pyglet +from f110_gym.envs import IntegratorType +from f110_gym.envs.action import (CarActionEnum, + from_single_to_multi_action_space) +# base classes +from f110_gym.envs.base_classes import DynamicModel, Simulator +from f110_gym.envs.observation import observation_factory +from f110_gym.envs.track import Track +from f110_gym.envs.utils import deep_update pyglet.options["debug_gl"] = False -from pyglet import gl # rendering VIDEO_W = 600 @@ -187,7 +180,6 @@ def __del__(self): """ Finalizer, does cleanup """ - pass @classmethod def default_config(cls) -> dict: diff --git a/gym/f110_gym/envs/f110_env_backup.py b/gym/f110_gym/envs/f110_env_backup.py index 5fd37721..56a7411c 100644 --- a/gym/f110_gym/envs/f110_env_backup.py +++ b/gym/f110_gym/envs/f110_env_backup.py @@ -24,31 +24,23 @@ Author: Hongrui Zheng """ -# gym imports -import gym -from gym import error, spaces, utils -from gym.utils import seeding - -# zmq imports -import zmq - -# protobuf import -import sim_requests_pb2 - -# others -import numpy as np - -from numba import njit -from scipy.ndimage import distance_transform_edt as edt - -from PIL import Image -import sys import os import signal import subprocess -import math +import sys + +# others +import numpy as np +# protobuf import +import sim_requests_pb2 import yaml -import csv +# zmq imports +import zmq +from PIL import Image + +# gym imports +import gym +from gym import utils # from matplotlib.pyplot import imshow # import matplotlib.pyplot as plt diff --git a/gym/f110_gym/envs/laser_models.py b/gym/f110_gym/envs/laser_models.py index 450a2967..6e4c5438 100644 --- a/gym/f110_gym/envs/laser_models.py +++ b/gym/f110_gym/envs/laser_models.py @@ -26,17 +26,12 @@ Author: Hongrui Zheng """ -import numpy as np -from numba import njit -from scipy.ndimage import distance_transform_edt as edt -from PIL import Image -import os -import yaml - import unittest -import timeit +import numpy as np from f110_gym.envs.track import Track +from numba import njit +from scipy.ndimage import distance_transform_edt as edt def get_dt(bitmap, resolution): diff --git a/gym/f110_gym/envs/rendering.py b/gym/f110_gym/envs/rendering.py index 44e06e4c..98f5c4f7 100644 --- a/gym/f110_gym/envs/rendering.py +++ b/gym/f110_gym/envs/rendering.py @@ -26,19 +26,14 @@ Author: Hongrui Zheng """ -# opengl stuff -import pyglet -from pyglet.gl import * - # other import numpy as np -from PIL import Image -import yaml - -from f110_gym.envs.track import Track - +# opengl stuff +import pyglet # helpers from f110_gym.envs.collision_models import get_vertices +from f110_gym.envs.track import Track +from pyglet.gl import * # zooming constants ZOOM_IN_FACTOR = 1.2 diff --git a/gym/f110_gym/envs/track.py b/gym/f110_gym/envs/track.py index e5e23c8a..b8bbb6d2 100644 --- a/gym/f110_gym/envs/track.py +++ b/gym/f110_gym/envs/track.py @@ -1,4 +1,3 @@ -import os import pathlib import tarfile from dataclasses import dataclass diff --git a/gym/f110_gym/envs/utils.py b/gym/f110_gym/envs/utils.py index 5b84e30d..2717354c 100644 --- a/gym/f110_gym/envs/utils.py +++ b/gym/f110_gym/envs/utils.py @@ -1,7 +1,5 @@ -from typing import Dict, Any - # types -from typing import TypeVar +from typing import Any, Dict, TypeVar KeyType = TypeVar("KeyType") diff --git a/pytest.ini b/pytest.ini deleted file mode 100644 index c1a1c8d2..00000000 --- a/pytest.ini +++ /dev/null @@ -1,6 +0,0 @@ -[pytest] -minversion = 6.0 -addopts = -ra -q -testpaths = - tests - integration \ No newline at end of file diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 00000000..645aa39a --- /dev/null +++ b/setup.cfg @@ -0,0 +1,16 @@ +[pytest] +minversion = 6.0 +addopts = -ra -q +testpaths = + tests + integration + +[flake8] +extend-ignore = E203, E501 +max-line-length = 120 +exclude = + .git, + __pycache__, + build, + dist +max-complexity = 10 \ No newline at end of file diff --git a/tests/legacy_scan_gen.py b/tests/legacy_scan_gen.py index 93c97e56..e69c8770 100644 --- a/tests/legacy_scan_gen.py +++ b/tests/legacy_scan_gen.py @@ -35,6 +35,7 @@ """ import numpy as np + import gym thetas = np.linspace(-2.35, 2.35, num=1080) diff --git a/tests/pyglet_test_.py b/tests/pyglet_test_.py index 8d0d355d..c1cac494 100644 --- a/tests/pyglet_test_.py +++ b/tests/pyglet_test_.py @@ -1,12 +1,11 @@ +import argparse + import numpy as np -from PIL import Image +import pyglet import yaml - +from PIL import Image +from pyglet import graphics, window from pyglet.gl import * -import pyglet -from pyglet import font, graphics, window - -import argparse class Camera: @@ -192,7 +191,6 @@ def on_resize(width, height): def loop(dt): print(pyglet.clock.get_fps()) - pass @window.event diff --git a/tests/test_collision_checks.py b/tests/test_collision_checks.py index e40e2f9c..8e7434bf 100644 --- a/tests/test_collision_checks.py +++ b/tests/test_collision_checks.py @@ -270,6 +270,7 @@ def test_get_vert(self, debug=False): rect = np.vstack((vertices, vertices[0, :])) if debug: import matplotlib.pyplot as plt + plt.scatter(test_pose[0], test_pose[1], c="red") plt.plot(rect[:, 0], rect[:, 1]) plt.xlim([1, 4]) diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 56ee4889..b3957d1e 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -19,11 +19,10 @@ Author: Hongrui Zheng """ -import numpy as np - -import unittest import time +import unittest +import numpy as np from f110_gym.envs import vehicle_dynamics_ks, vehicle_dynamics_st diff --git a/tests/test_f110_env.py b/tests/test_f110_env.py index e47f97d8..f2a56957 100644 --- a/tests/test_f110_env.py +++ b/tests/test_f110_env.py @@ -1,17 +1,12 @@ -import pathlib import unittest -from argparse import Namespace -import numpy as np -import yaml import gymnasium as gym - +import numpy as np from f110_gym.envs.utils import deep_update class TestEnvInterface(unittest.TestCase): def _make_env(self, config={}): - import f110_gym conf = { "map": "Example", @@ -40,7 +35,6 @@ def test_configure_method(self): Test that the configure method works as expected, and that the parameters are correctly updated in the simulator and agents. """ - import f110_gym # create a base environment and use configure() to change the width config_ext = {"params": {"width": 15.0}} diff --git a/tests/test_observation.py b/tests/test_observation.py index 9a7c02cf..3d047bca 100644 --- a/tests/test_observation.py +++ b/tests/test_observation.py @@ -1,22 +1,16 @@ -import pathlib import unittest -from argparse import Namespace +import gymnasium as gym import numpy as np -import yaml -from gymnasium.spaces import Box - from f110_gym.envs import F110Env -from f110_gym.envs.observation import FeaturesObservation, observation_factory -import gymnasium as gym - +from f110_gym.envs.observation import observation_factory from f110_gym.envs.utils import deep_update +from gymnasium.spaces import Box class TestObservationInterface(unittest.TestCase): @staticmethod def _make_env(config={}) -> F110Env: - import f110_gym conf = { "map": "Example", @@ -227,9 +221,7 @@ def test_consistency_observe_space(self): ) def test_gymnasium_api(self): - import f110_gym from gymnasium.utils.env_checker import check_env - import gymnasium as gym obs_type_ids = ["kinematic_state", "dynamic_state", "original"] diff --git a/tests/test_scan_sim.py b/tests/test_scan_sim.py index dab88b57..b41345c9 100644 --- a/tests/test_scan_sim.py +++ b/tests/test_scan_sim.py @@ -25,17 +25,13 @@ Author: Hongrui Zheng """ -import numpy as np -from numba import njit -from scipy.ndimage import distance_transform_edt as edt -from PIL import Image import os -import yaml - import unittest -import timeit +import numpy as np from f110_gym.envs import ScanSimulator2D +from numba import njit +from scipy.ndimage import distance_transform_edt as edt def get_dt(bitmap, resolution): @@ -254,11 +250,12 @@ def get_scan( Author: Hongrui Zheng Test cases: - 1, 2: Comparison between generated scan array of the new simulator and the legacy C++ simulator, + 1, 2: Comparison between generated scan array of the new simulator and the legacy C++ simulator, generated data used, MSE is used as the metric 2. FPS test, should be greater than 500 """ + class ScanTests(unittest.TestCase): def setUp(self): # test params @@ -389,4 +386,4 @@ def update(i): if __name__ == "__main__": # test.main() - main() \ No newline at end of file + main() diff --git a/tests/test_track.py b/tests/test_track.py index 06c66d58..0aeab271 100644 --- a/tests/test_track.py +++ b/tests/test_track.py @@ -3,8 +3,7 @@ import unittest import numpy as np - -from f110_gym.envs.track import Track, find_track_dir, Raceline +from f110_gym.envs.track import Raceline, Track, find_track_dir class TestTrack(unittest.TestCase): diff --git a/tests/test_utils.py b/tests/test_utils.py index 2ed2f586..c2fefbe5 100644 --- a/tests/test_utils.py +++ b/tests/test_utils.py @@ -7,7 +7,6 @@ def test_deep_update(self): Test that the deep_update function works as expected with nested dictionaries, by comparing two environments with different mu values. """ - import f110_gym import gymnasium as gym default_env = gym.make("f110_gym:f110-v0") From 6fbd313d78162e5cef7f4a8faac3cb3d7279482e Mon Sep 17 00:00:00 2001 From: nandantumu Date: Tue, 22 Aug 2023 20:03:44 -0400 Subject: [PATCH 15/32] Updated requirements --- Pipfile | 2 ++ Pipfile.lock | 61 +++++++++++++++++++++++++++++++++++++++++++++++- requirements.txt | 36 ++++++++++++++++++++++++++++ setup.cfg | 3 +-- 4 files changed, 99 insertions(+), 3 deletions(-) diff --git a/Pipfile b/Pipfile index a191989d..0e23284b 100644 --- a/Pipfile +++ b/Pipfile @@ -16,6 +16,8 @@ requests = "*" pyopengl = "*" numba = "*" f110-gym = {file = "."} +shapely = "*" +opencv-python = "*" [dev-packages] flake8 = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 4a2c7255..4b8b43c0 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "cf830ecdf81a7befa15768216c25db2cb59af898f4cf869fe4e59f3dd569a008" + "sha256": "c9fa7363e2c9280dcaeeef6720666831d1b9a1e0843b3f936486f7996f813355" }, "pipfile-spec": 6, "requires": { @@ -483,6 +483,20 @@ "markers": "python_version >= '3.8'", "version": "==1.24.4" }, + "opencv-python": { + "hashes": [ + "sha256:48eb3121d809a873086d6677565e3ac963e6946110d13cd115533fa70e2aa2eb", + "sha256:56d84c43ce800938b9b1ec74b33942b2edbcef3f70c2754eb9bfe5dff1ee3ace", + "sha256:67bce4b9aad307c98a9a07c6afb7de3a4e823c1f4991d6d8e88e229e7dfeee59", + "sha256:93871871b1c9d6b125cddd45b0638a2fa01ee9fd37f5e428823f750e404f2f15", + "sha256:9bcb4944211acf13742dbfd9d3a11dc4e36353ffa1746f2c7dcd6a01c32d1376", + "sha256:b2349dc9f97ed6c9ba163d0a7a24bcef9695a3e216cd143e92f1b9659c5d9a49", + "sha256:ba32cfa75a806abd68249699d34420737d27b5678553387fc5768747a6492147" + ], + "index": "pypi", + "markers": "python_version >= '3.6'", + "version": "==4.8.0.76" + }, "packaging": { "hashes": [ "sha256:994793af429502c4ea2ebf6bf664629d07c1a9fe974af92966e4b8d2df7edc61", @@ -674,6 +688,51 @@ "markers": "python_version < '3.13' and python_version >= '3.9'", "version": "==1.11.2" }, + "shapely": { + "hashes": [ + "sha256:01224899ff692a62929ef1a3f5fe389043e262698a708ab7569f43a99a48ae82", + "sha256:05c51a29336e604c084fb43ae5dbbfa2c0ef9bd6fedeae0a0d02c7b57a56ba46", + "sha256:09d6c7763b1bee0d0a2b84bb32a4c25c6359ad1ac582a62d8b211e89de986154", + "sha256:193a398d81c97a62fc3634a1a33798a58fd1dcf4aead254d080b273efbb7e3ff", + "sha256:1a34a23d6266ca162499e4a22b79159dc0052f4973d16f16f990baa4d29e58b6", + "sha256:2569a4b91caeef54dd5ae9091ae6f63526d8ca0b376b5bb9fd1a3195d047d7d4", + "sha256:33403b8896e1d98aaa3a52110d828b18985d740cc9f34f198922018b1e0f8afe", + "sha256:3ad81f292fffbd568ae71828e6c387da7eb5384a79db9b4fde14dd9fdeffca9a", + "sha256:3cb256ae0c01b17f7bc68ee2ffdd45aebf42af8992484ea55c29a6151abe4386", + "sha256:45b4833235b90bc87ee26c6537438fa77559d994d2d3be5190dd2e54d31b2820", + "sha256:4641325e065fd3e07d55677849c9ddfd0cf3ee98f96475126942e746d55b17c8", + "sha256:502e0a607f1dcc6dee0125aeee886379be5242c854500ea5fd2e7ac076b9ce6d", + "sha256:66a6b1a3e72ece97fc85536a281476f9b7794de2e646ca8a4517e2e3c1446893", + "sha256:70a18fc7d6418e5aea76ac55dce33f98e75bd413c6eb39cfed6a1ba36469d7d4", + "sha256:7d3bbeefd8a6a1a1017265d2d36f8ff2d79d0162d8c141aa0d37a87063525656", + "sha256:83a8ec0ee0192b6e3feee9f6a499d1377e9c295af74d7f81ecba5a42a6b195b7", + "sha256:865bc3d7cc0ea63189d11a0b1120d1307ed7a64720a8bfa5be2fde5fc6d0d33f", + "sha256:90cfa4144ff189a3c3de62e2f3669283c98fb760cfa2e82ff70df40f11cadb39", + "sha256:91575d97fd67391b85686573d758896ed2fc7476321c9d2e2b0c398b628b961c", + "sha256:9a6ac34c16f4d5d3c174c76c9d7614ec8fe735f8f82b6cc97a46b54f386a86bf", + "sha256:a529218e72a3dbdc83676198e610485fdfa31178f4be5b519a8ae12ea688db14", + "sha256:a70a614791ff65f5e283feed747e1cc3d9e6c6ba91556e640636bbb0a1e32a71", + "sha256:ac1dfc397475d1de485e76de0c3c91cc9d79bd39012a84bb0f5e8a199fc17bef", + "sha256:b06d031bc64149e340448fea25eee01360a58936c89985cf584134171e05863f", + "sha256:b4f0711cc83734c6fad94fc8d4ec30f3d52c1787b17d9dca261dc841d4731c64", + "sha256:b50c401b64883e61556a90b89948297f1714dbac29243d17ed9284a47e6dd731", + "sha256:b519cf3726ddb6c67f6a951d1bb1d29691111eaa67ea19ddca4d454fbe35949c", + "sha256:bca57b683e3d94d0919e2f31e4d70fdfbb7059650ef1b431d9f4e045690edcd5", + "sha256:c43755d2c46b75a7b74ac6226d2cc9fa2a76c3263c5ae70c195c6fb4e7b08e79", + "sha256:c7eed1fb3008a8a4a56425334b7eb82651a51f9e9a9c2f72844a2fb394f38a6c", + "sha256:c8b0d834b11be97d5ab2b4dceada20ae8e07bcccbc0f55d71df6729965f406ad", + "sha256:ce88ec79df55430e37178a191ad8df45cae90b0f6972d46d867bf6ebbb58cc4d", + "sha256:d173d24e85e51510e658fb108513d5bc11e3fd2820db6b1bd0522266ddd11f51", + "sha256:d8f55f355be7821dade839df785a49dc9f16d1af363134d07eb11e9207e0b189", + "sha256:da71de5bf552d83dcc21b78cc0020e86f8d0feea43e202110973987ffa781c21", + "sha256:e55698e0ed95a70fe9ff9a23c763acfe0bf335b02df12142f74e4543095e9a9b", + "sha256:f32a748703e7bf6e92dfa3d2936b2fbfe76f8ce5f756e24f49ef72d17d26ad02", + "sha256:f470a130d6ddb05b810fc1776d918659407f8d025b7f56d2742a596b6dffa6c7" + ], + "index": "pypi", + "markers": "python_version >= '3.7'", + "version": "==2.0.1" + }, "six": { "hashes": [ "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926", diff --git a/requirements.txt b/requirements.txt index 0f2dd6a3..cbd0f662 100644 --- a/requirements.txt +++ b/requirements.txt @@ -32,3 +32,39 @@ typing-extensions==4.7.1; python_version >= '3.7' typing-inspect==0.9.0 urllib3==2.0.4; python_version >= '3.7' yamldataclassconfig==1.5.0; python_version >= '3.7' +-i https://pypi.org/simple +certifi==2023.7.22; python_version >= '3.6' +charset-normalizer==3.2.0; python_full_version >= '3.7.0' +cloudpickle==2.2.1; python_version >= '3.6' +contourpy==1.1.0; python_version >= '3.8' +cycler==0.11.0; python_version >= '3.6' +dataclasses-json==0.5.14; python_version < '3.13' and python_version >= '3.7' +-e . +farama-notifications==0.0.4 +fonttools==4.42.1; python_version >= '3.8' +future==0.18.3; python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3' +gymnasium==0.29.1; python_version >= '3.8' +idna==3.4; python_version >= '3.5' +kiwisolver==1.4.4; python_version >= '3.7' +llvmlite==0.40.1; python_version >= '3.8' +marshmallow==3.20.1; python_version >= '3.8' +matplotlib==3.7.2; python_version >= '3.8' +mypy-extensions==1.0.0; python_version >= '3.5' +numba==0.57.1; python_version >= '3.8' +numpy==1.24.4; python_version >= '3.8' +opencv-python==4.8.0.76; python_version >= '3.6' +packaging==23.1; python_version >= '3.7' +pillow==10.0.0; python_version >= '3.8' +pyglet==1.4.11 +pyopengl==3.1.7 +pyparsing==3.0.9; python_full_version >= '3.6.8' +python-dateutil==2.8.2; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' +pyyaml==6.0.1; python_version >= '3.6' +requests==2.31.0; python_version >= '3.7' +scipy==1.11.2; python_version < '3.13' and python_version >= '3.9' +shapely==2.0.1; python_version >= '3.7' +six==1.16.0; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' +typing-extensions==4.7.1; python_version >= '3.7' +typing-inspect==0.9.0 +urllib3==2.0.4; python_version >= '3.7' +yamldataclassconfig==1.5.0; python_version >= '3.7' diff --git a/setup.cfg b/setup.cfg index 645aa39a..259f3aee 100644 --- a/setup.cfg +++ b/setup.cfg @@ -12,5 +12,4 @@ exclude = .git, __pycache__, build, - dist -max-complexity = 10 \ No newline at end of file + dist \ No newline at end of file From 1a2a5c99133d54e2a922a7905c87bac0c070359d Mon Sep 17 00:00:00 2001 From: nandantumu Date: Wed, 23 Aug 2023 11:53:28 -0400 Subject: [PATCH 16/32] Fixed requirements, updated imports --- Pipfile | 4 +- Pipfile.lock | 594 +++++++++++++++++------------- gym/f110_gym/envs/__init__.py | 1 + gym/f110_gym/envs/base_classes.py | 2 +- gym/f110_gym/envs/f110_env.py | 2 +- requirements.txt | 70 ---- setup.cfg | 2 +- setup.py | 13 + tests/test_dynamics.py | 2 +- tests/test_scan_sim.py | 2 +- 10 files changed, 359 insertions(+), 333 deletions(-) delete mode 100644 requirements.txt diff --git a/Pipfile b/Pipfile index 0e23284b..b85b85fa 100644 --- a/Pipfile +++ b/Pipfile @@ -11,13 +11,12 @@ scipy = ">=1.7.3" pyglet = "<1.5" pyyaml = ">=5.3.1" yamldataclassconfig = "*" -matplotlib = "*" requests = "*" pyopengl = "*" numba = "*" -f110-gym = {file = "."} shapely = "*" opencv-python = "*" +f110-gym = {file = "."} [dev-packages] flake8 = "*" @@ -26,6 +25,7 @@ ipykernel = "*" pytest = "*" isort = "*" autoflake = "*" +matplotlib = "*" [requires] python_version = "3.10" diff --git a/Pipfile.lock b/Pipfile.lock index 4b8b43c0..5950f0cd 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "c9fa7363e2c9280dcaeeef6720666831d1b9a1e0843b3f936486f7996f813355" + "sha256": "8ba9fc82f4b3c300687f74e53209cf8bf21995882ac9cde2b005fd30b579e7ec" }, "pipfile-spec": 6, "requires": { @@ -114,59 +114,6 @@ "markers": "python_version >= '3.6'", "version": "==2.2.1" }, - "contourpy": { - "hashes": [ - "sha256:052cc634bf903c604ef1a00a5aa093c54f81a2612faedaa43295809ffdde885e", - "sha256:084eaa568400cfaf7179b847ac871582199b1b44d5699198e9602ecbbb5f6104", - "sha256:0b6616375d7de55797d7a66ee7d087efe27f03d336c27cf1f32c02b8c1a5ac70", - "sha256:0b7b04ed0961647691cfe5d82115dd072af7ce8846d31a5fac6c142dcce8b882", - "sha256:143dde50520a9f90e4a2703f367cf8ec96a73042b72e68fcd184e1279962eb6f", - "sha256:17cfaf5ec9862bc93af1ec1f302457371c34e688fbd381f4035a06cd47324f48", - "sha256:181cbace49874f4358e2929aaf7ba84006acb76694102e88dd15af861996c16e", - "sha256:189ceb1525eb0655ab8487a9a9c41f42a73ba52d6789754788d1883fb06b2d8a", - "sha256:18a64814ae7bce73925131381603fff0116e2df25230dfc80d6d690aa6e20b37", - "sha256:1f0cbd657e9bde94cd0e33aa7df94fb73c1ab7799378d3b3f902eb8eb2e04a3a", - "sha256:1f795597073b09d631782e7245016a4323cf1cf0b4e06eef7ea6627e06a37ff2", - "sha256:25ae46595e22f93592d39a7eac3d638cda552c3e1160255258b695f7b58e5655", - "sha256:27bc79200c742f9746d7dd51a734ee326a292d77e7d94c8af6e08d1e6c15d545", - "sha256:2b836d22bd2c7bb2700348e4521b25e077255ebb6ab68e351ab5aa91ca27e027", - "sha256:30f511c05fab7f12e0b1b7730ebdc2ec8deedcfb505bc27eb570ff47c51a8f15", - "sha256:317267d915490d1e84577924bd61ba71bf8681a30e0d6c545f577363157e5e94", - "sha256:397b0ac8a12880412da3551a8cb5a187d3298a72802b45a3bd1805e204ad8439", - "sha256:438ba416d02f82b692e371858143970ed2eb6337d9cdbbede0d8ad9f3d7dd17d", - "sha256:53cc3a40635abedbec7f1bde60f8c189c49e84ac180c665f2cd7c162cc454baa", - "sha256:5d123a5bc63cd34c27ff9c7ac1cd978909e9c71da12e05be0231c608048bb2ae", - "sha256:62013a2cf68abc80dadfd2307299bfa8f5aa0dcaec5b2954caeb5fa094171103", - "sha256:89f06eff3ce2f4b3eb24c1055a26981bffe4e7264acd86f15b97e40530b794bc", - "sha256:90c81f22b4f572f8a2110b0b741bb64e5a6427e0a198b2cdc1fbaf85f352a3aa", - "sha256:911ff4fd53e26b019f898f32db0d4956c9d227d51338fb3b03ec72ff0084ee5f", - "sha256:9382a1c0bc46230fb881c36229bfa23d8c303b889b788b939365578d762b5c18", - "sha256:9f2931ed4741f98f74b410b16e5213f71dcccee67518970c42f64153ea9313b9", - "sha256:a67259c2b493b00e5a4d0f7bfae51fb4b3371395e47d079a4446e9b0f4d70e76", - "sha256:a698c6a7a432789e587168573a864a7ea374c6be8d4f31f9d87c001d5a843493", - "sha256:bc00bb4225d57bff7ebb634646c0ee2a1298402ec10a5fe7af79df9a51c1bfd9", - "sha256:bcb41692aa09aeb19c7c213411854402f29f6613845ad2453d30bf421fe68fed", - "sha256:d4f26b25b4f86087e7d75e63212756c38546e70f2a92d2be44f80114826e1cd4", - "sha256:d551f3a442655f3dcc1285723f9acd646ca5858834efeab4598d706206b09c9f", - "sha256:dffcc2ddec1782dd2f2ce1ef16f070861af4fb78c69862ce0aab801495dda6a3", - "sha256:e53046c3863828d21d531cc3b53786e6580eb1ba02477e8681009b6aa0870b21", - "sha256:e5cec36c5090e75a9ac9dbd0ff4a8cf7cecd60f1b6dc23a374c7d980a1cd710e", - "sha256:e7a117ce7df5a938fe035cad481b0189049e8d92433b4b33aa7fc609344aafa1", - "sha256:e94bef2580e25b5fdb183bf98a2faa2adc5b638736b2c0a4da98691da641316a", - "sha256:ed614aea8462735e7d70141374bd7650afd1c3f3cb0c2dbbcbe44e14331bf002", - "sha256:fb3b7d9e6243bfa1efb93ccfe64ec610d85cfe5aec2c25f97fbbd2e58b531256" - ], - "markers": "python_version >= '3.8'", - "version": "==1.1.0" - }, - "cycler": { - "hashes": [ - "sha256:3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3", - "sha256:9c87405839a19696e837b3b818fed3f5f69f16f1eec1a1ad77e043dcea9c772f" - ], - "markers": "python_version >= '3.6'", - "version": "==0.11.0" - }, "dataclasses-json": { "hashes": [ "sha256:5ec6fed642adb1dbdb4182badb01e0861badfd8fda82e3b67f44b2d1e9d10d21", @@ -185,46 +132,6 @@ ], "version": "==0.0.4" }, - "fonttools": { - "hashes": [ - "sha256:0eb79a2da5eb6457a6f8ab904838454accc7d4cccdaff1fd2bd3a0679ea33d64", - "sha256:113337c2d29665839b7d90b39f99b3cac731f72a0eda9306165a305c7c31d341", - "sha256:12a7c247d1b946829bfa2f331107a629ea77dc5391dfd34fdcd78efa61f354ca", - "sha256:179737095eb98332a2744e8f12037b2977f22948cf23ff96656928923ddf560a", - "sha256:19b7db825c8adee96fac0692e6e1ecd858cae9affb3b4812cdb9d934a898b29e", - "sha256:37983b6bdab42c501202500a2be3a572f50d4efe3237e0686ee9d5f794d76b35", - "sha256:3a35981d90feebeaef05e46e33e6b9e5b5e618504672ca9cd0ff96b171e4bfff", - "sha256:46a0ec8adbc6ff13494eb0c9c2e643b6f009ce7320cf640de106fb614e4d4360", - "sha256:4aa79366e442dbca6e2c8595645a3a605d9eeabdb7a094d745ed6106816bef5d", - "sha256:515607ec756d7865f23070682622c49d922901943697871fc292277cf1e71967", - "sha256:53eb5091ddc8b1199330bb7b4a8a2e7995ad5d43376cadce84523d8223ef3136", - "sha256:5d18fc642fd0ac29236ff88ecfccff229ec0386090a839dd3f1162e9a7944a40", - "sha256:5fb289b7a815638a7613d46bcf324c9106804725b2bb8ad913c12b6958ffc4ec", - "sha256:62f481ac772fd68901573956231aea3e4b1ad87b9b1089a61613a91e2b50bb9b", - "sha256:689508b918332fb40ce117131633647731d098b1b10d092234aa959b4251add5", - "sha256:68a02bbe020dc22ee0540e040117535f06df9358106d3775e8817d826047f3fd", - "sha256:6ed2662a3d9c832afa36405f8748c250be94ae5dfc5283d668308391f2102861", - "sha256:7286aed4ea271df9eab8d7a9b29e507094b51397812f7ce051ecd77915a6e26b", - "sha256:7cc7d685b8eeca7ae69dc6416833fbfea61660684b7089bca666067cb2937dcf", - "sha256:8708b98c278012ad267ee8a7433baeb809948855e81922878118464b274c909d", - "sha256:9398f244e28e0596e2ee6024f808b06060109e33ed38dcc9bded452fd9bbb853", - "sha256:9e36344e48af3e3bde867a1ca54f97c308735dd8697005c2d24a86054a114a71", - "sha256:a398bdadb055f8de69f62b0fc70625f7cbdab436bbb31eef5816e28cab083ee8", - "sha256:acb47f6f8680de24c1ab65ebde39dd035768e2a9b571a07c7b8da95f6c8815fd", - "sha256:be24fcb80493b2c94eae21df70017351851652a37de514de553435b256b2f249", - "sha256:c391cd5af88aacaf41dd7cfb96eeedfad297b5899a39e12f4c2c3706d0a3329d", - "sha256:c95b0724a6deea2c8c5d3222191783ced0a2f09bd6d33f93e563f6f1a4b3b3a4", - "sha256:c9b1ce7a45978b821a06d375b83763b27a3a5e8a2e4570b3065abad240a18760", - "sha256:db372213d39fa33af667c2aa586a0c1235e88e9c850f5dd5c8e1f17515861868", - "sha256:db55cbaea02a20b49fefbd8e9d62bd481aaabe1f2301dabc575acc6b358874fa", - "sha256:ed1a13a27f59d1fc1920394a7f596792e9d546c9ca5a044419dca70c37815d7c", - "sha256:f2b82f46917d8722e6b5eafeefb4fb585d23babd15d8246c664cd88a5bddd19c", - "sha256:f2f806990160d1ce42d287aa419df3ffc42dfefe60d473695fb048355fe0c6a0", - "sha256:f720fa82a11c0f9042376fd509b5ed88dab7e3cd602eee63a1af08883b37342b" - ], - "markers": "python_version >= '3.8'", - "version": "==4.42.1" - }, "future": { "hashes": [ "sha256:34a17436ed1e96697a86f9de3d15a3b0be01d8bc8de9c1dffd59fb8234ed5307" @@ -249,80 +156,6 @@ "markers": "python_version >= '3.5'", "version": "==3.4" }, - "kiwisolver": { - "hashes": [ - "sha256:02f79693ec433cb4b5f51694e8477ae83b3205768a6fb48ffba60549080e295b", - "sha256:03baab2d6b4a54ddbb43bba1a3a2d1627e82d205c5cf8f4c924dc49284b87166", - "sha256:1041feb4cda8708ce73bb4dcb9ce1ccf49d553bf87c3954bdfa46f0c3f77252c", - "sha256:10ee06759482c78bdb864f4109886dff7b8a56529bc1609d4f1112b93fe6423c", - "sha256:1d1573129aa0fd901076e2bfb4275a35f5b7aa60fbfb984499d661ec950320b0", - "sha256:283dffbf061a4ec60391d51e6155e372a1f7a4f5b15d59c8505339454f8989e4", - "sha256:28bc5b299f48150b5f822ce68624e445040595a4ac3d59251703779836eceff9", - "sha256:2a66fdfb34e05b705620dd567f5a03f239a088d5a3f321e7b6ac3239d22aa286", - "sha256:2e307eb9bd99801f82789b44bb45e9f541961831c7311521b13a6c85afc09767", - "sha256:2e407cb4bd5a13984a6c2c0fe1845e4e41e96f183e5e5cd4d77a857d9693494c", - "sha256:2f5e60fabb7343a836360c4f0919b8cd0d6dbf08ad2ca6b9cf90bf0c76a3c4f6", - "sha256:36dafec3d6d6088d34e2de6b85f9d8e2324eb734162fba59d2ba9ed7a2043d5b", - "sha256:3fe20f63c9ecee44560d0e7f116b3a747a5d7203376abeea292ab3152334d004", - "sha256:41dae968a94b1ef1897cb322b39360a0812661dba7c682aa45098eb8e193dbdf", - "sha256:4bd472dbe5e136f96a4b18f295d159d7f26fd399136f5b17b08c4e5f498cd494", - "sha256:4ea39b0ccc4f5d803e3337dd46bcce60b702be4d86fd0b3d7531ef10fd99a1ac", - "sha256:5853eb494c71e267912275e5586fe281444eb5e722de4e131cddf9d442615626", - "sha256:5bce61af018b0cb2055e0e72e7d65290d822d3feee430b7b8203d8a855e78766", - "sha256:6295ecd49304dcf3bfbfa45d9a081c96509e95f4b9d0eb7ee4ec0530c4a96514", - "sha256:62ac9cc684da4cf1778d07a89bf5f81b35834cb96ca523d3a7fb32509380cbf6", - "sha256:70e7c2e7b750585569564e2e5ca9845acfaa5da56ac46df68414f29fea97be9f", - "sha256:7577c1987baa3adc4b3c62c33bd1118c3ef5c8ddef36f0f2c950ae0b199e100d", - "sha256:75facbe9606748f43428fc91a43edb46c7ff68889b91fa31f53b58894503a191", - "sha256:787518a6789009c159453da4d6b683f468ef7a65bbde796bcea803ccf191058d", - "sha256:78d6601aed50c74e0ef02f4204da1816147a6d3fbdc8b3872d263338a9052c51", - "sha256:7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f", - "sha256:81e38381b782cc7e1e46c4e14cd997ee6040768101aefc8fa3c24a4cc58e98f8", - "sha256:841293b17ad704d70c578f1f0013c890e219952169ce8a24ebc063eecf775454", - "sha256:872b8ca05c40d309ed13eb2e582cab0c5a05e81e987ab9c521bf05ad1d5cf5cb", - "sha256:877272cf6b4b7e94c9614f9b10140e198d2186363728ed0f701c6eee1baec1da", - "sha256:8c808594c88a025d4e322d5bb549282c93c8e1ba71b790f539567932722d7bd8", - "sha256:8ed58b8acf29798b036d347791141767ccf65eee7f26bde03a71c944449e53de", - "sha256:91672bacaa030f92fc2f43b620d7b337fd9a5af28b0d6ed3f77afc43c4a64b5a", - "sha256:968f44fdbf6dd757d12920d63b566eeb4d5b395fd2d00d29d7ef00a00582aac9", - "sha256:9f85003f5dfa867e86d53fac6f7e6f30c045673fa27b603c397753bebadc3008", - "sha256:a553dadda40fef6bfa1456dc4be49b113aa92c2a9a9e8711e955618cd69622e3", - "sha256:a68b62a02953b9841730db7797422f983935aeefceb1679f0fc85cbfbd311c32", - "sha256:abbe9fa13da955feb8202e215c4018f4bb57469b1b78c7a4c5c7b93001699938", - "sha256:ad881edc7ccb9d65b0224f4e4d05a1e85cf62d73aab798943df6d48ab0cd79a1", - "sha256:b1792d939ec70abe76f5054d3f36ed5656021dcad1322d1cc996d4e54165cef9", - "sha256:b428ef021242344340460fa4c9185d0b1f66fbdbfecc6c63eff4b7c29fad429d", - "sha256:b533558eae785e33e8c148a8d9921692a9fe5aa516efbdff8606e7d87b9d5824", - "sha256:ba59c92039ec0a66103b1d5fe588fa546373587a7d68f5c96f743c3396afc04b", - "sha256:bc8d3bd6c72b2dd9decf16ce70e20abcb3274ba01b4e1c96031e0c4067d1e7cd", - "sha256:bc9db8a3efb3e403e4ecc6cd9489ea2bac94244f80c78e27c31dcc00d2790ac2", - "sha256:bf7d9fce9bcc4752ca4a1b80aabd38f6d19009ea5cbda0e0856983cf6d0023f5", - "sha256:c2dbb44c3f7e6c4d3487b31037b1bdbf424d97687c1747ce4ff2895795c9bf69", - "sha256:c79ebe8f3676a4c6630fd3f777f3cfecf9289666c84e775a67d1d358578dc2e3", - "sha256:c97528e64cb9ebeff9701e7938653a9951922f2a38bd847787d4a8e498cc83ae", - "sha256:d0611a0a2a518464c05ddd5a3a1a0e856ccc10e67079bb17f265ad19ab3c7597", - "sha256:d06adcfa62a4431d404c31216f0f8ac97397d799cd53800e9d3efc2fbb3cf14e", - "sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955", - "sha256:d5b61785a9ce44e5a4b880272baa7cf6c8f48a5180c3e81c59553ba0cb0821ca", - "sha256:da152d8cdcab0e56e4f45eb08b9aea6455845ec83172092f09b0e077ece2cf7a", - "sha256:da7e547706e69e45d95e116e6939488d62174e033b763ab1496b4c29b76fabea", - "sha256:db5283d90da4174865d520e7366801a93777201e91e79bacbac6e6927cbceede", - "sha256:db608a6757adabb32f1cfe6066e39b3706d8c3aa69bbc353a5b61edad36a5cb4", - "sha256:e0ea21f66820452a3f5d1655f8704a60d66ba1191359b96541eaf457710a5fc6", - "sha256:e7da3fec7408813a7cebc9e4ec55afed2d0fd65c4754bc376bf03498d4e92686", - "sha256:e92a513161077b53447160b9bd8f522edfbed4bd9759e4c18ab05d7ef7e49408", - "sha256:ecb1fa0db7bf4cff9dac752abb19505a233c7f16684c5826d1f11ebd9472b871", - "sha256:efda5fc8cc1c61e4f639b8067d118e742b812c930f708e6667a5ce0d13499e29", - "sha256:f0a1dbdb5ecbef0d34eb77e56fcb3e95bbd7e50835d9782a45df81cc46949750", - "sha256:f0a71d85ecdd570ded8ac3d1c0f480842f49a40beb423bb8014539a9f32a5897", - "sha256:f4f270de01dd3e129a72efad823da90cc4d6aafb64c410c9033aba70db9f1ff0", - "sha256:f6cb459eea32a4e2cf18ba5fcece2dbdf496384413bc1bae15583f19e567f3b2", - "sha256:f8ad8285b01b0d4695102546b342b493b3ccc6781fc28c8c6a1bb63e95d22f09", - "sha256:f9f39e2f049db33a908319cf46624a569b36983c7c78318e9726a4cb8923b26c" - ], - "markers": "python_version >= '3.7'", - "version": "==1.4.4" - }, "llvmlite": { "hashes": [ "sha256:09f83ea7a54509c285f905d968184bba00fc31ebf12f2b6b1494d677bb7dde9b", @@ -361,54 +194,6 @@ "markers": "python_version >= '3.8'", "version": "==3.20.1" }, - "matplotlib": { - "hashes": [ - "sha256:070f8dddd1f5939e60aacb8fa08f19551f4b0140fab16a3669d5cd6e9cb28fc8", - "sha256:0c3cca3e842b11b55b52c6fb8bd6a4088693829acbfcdb3e815fa9b7d5c92c1b", - "sha256:0f506a1776ee94f9e131af1ac6efa6e5bc7cb606a3e389b0ccb6e657f60bb676", - "sha256:12f01b92ecd518e0697da4d97d163b2b3aa55eb3eb4e2c98235b3396d7dad55f", - "sha256:152ee0b569a37630d8628534c628456b28686e085d51394da6b71ef84c4da201", - "sha256:1c308b255efb9b06b23874236ec0f10f026673ad6515f602027cc8ac7805352d", - "sha256:1cd120fca3407a225168238b790bd5c528f0fafde6172b140a2f3ab7a4ea63e9", - "sha256:20f844d6be031948148ba49605c8b96dfe7d3711d1b63592830d650622458c11", - "sha256:23fb1750934e5f0128f9423db27c474aa32534cec21f7b2153262b066a581fd1", - "sha256:2699f7e73a76d4c110f4f25be9d2496d6ab4f17345307738557d345f099e07de", - "sha256:26bede320d77e469fdf1bde212de0ec889169b04f7f1179b8930d66f82b30cbc", - "sha256:2ecb5be2b2815431c81dc115667e33da0f5a1bcf6143980d180d09a717c4a12e", - "sha256:2f8e4a49493add46ad4a8c92f63e19d548b2b6ebbed75c6b4c7f46f57d36cdd1", - "sha256:305e3da477dc8607336ba10bac96986d6308d614706cae2efe7d3ffa60465b24", - "sha256:30e1409b857aa8a747c5d4f85f63a79e479835f8dffc52992ac1f3f25837b544", - "sha256:318c89edde72ff95d8df67d82aca03861240512994a597a435a1011ba18dbc7f", - "sha256:35d74ebdb3f71f112b36c2629cf32323adfbf42679e2751252acd468f5001c07", - "sha256:50e0a55ec74bf2d7a0ebf50ac580a209582c2dd0f7ab51bc270f1b4a0027454e", - "sha256:5dea00b62d28654b71ca92463656d80646675628d0828e08a5f3b57e12869e13", - "sha256:60c521e21031632aa0d87ca5ba0c1c05f3daacadb34c093585a0be6780f698e4", - "sha256:6515e878f91894c2e4340d81f0911857998ccaf04dbc1bba781e3d89cbf70608", - "sha256:6d2ff3c984b8a569bc1383cd468fc06b70d7b59d5c2854ca39f1436ae8394117", - "sha256:71667eb2ccca4c3537d9414b1bc00554cb7f91527c17ee4ec38027201f8f1603", - "sha256:717157e61b3a71d3d26ad4e1770dc85156c9af435659a25ee6407dc866cb258d", - "sha256:71f7a8c6b124e904db550f5b9fe483d28b896d4135e45c4ea381ad3b8a0e3256", - "sha256:936bba394682049919dda062d33435b3be211dc3dcaa011e09634f060ec878b2", - "sha256:a1733b8e84e7e40a9853e505fe68cc54339f97273bdfe6f3ed980095f769ddc7", - "sha256:a2c1590b90aa7bd741b54c62b78de05d4186271e34e2377e0289d943b3522273", - "sha256:a7e28d6396563955f7af437894a36bf2b279462239a41028323e04b85179058b", - "sha256:a8035ba590658bae7562786c9cc6ea1a84aa49d3afab157e414c9e2ea74f496d", - "sha256:a8cdb91dddb04436bd2f098b8fdf4b81352e68cf4d2c6756fcc414791076569b", - "sha256:ac60daa1dc83e8821eed155796b0f7888b6b916cf61d620a4ddd8200ac70cd64", - "sha256:af4860132c8c05261a5f5f8467f1b269bf1c7c23902d75f2be57c4a7f2394b3e", - "sha256:bc221ffbc2150458b1cd71cdd9ddd5bb37962b036e41b8be258280b5b01da1dd", - "sha256:ce55289d5659b5b12b3db4dc9b7075b70cef5631e56530f14b2945e8836f2d20", - "sha256:d9881356dc48e58910c53af82b57183879129fa30492be69058c5b0d9fddf391", - "sha256:dbcf59334ff645e6a67cd5f78b4b2cdb76384cdf587fa0d2dc85f634a72e1a3e", - "sha256:ebf577c7a6744e9e1bd3fee45fc74a02710b214f94e2bde344912d85e0c9af7c", - "sha256:f081c03f413f59390a80b3e351cc2b2ea0205839714dbc364519bcf51f4b56ca", - "sha256:fdbb46fad4fb47443b5b8ac76904b2e7a66556844f33370861b4788db0f8816a", - "sha256:fdcd28360dbb6203fb5219b1a5658df226ac9bebc2542a9e8f457de959d713d0" - ], - "index": "pypi", - "markers": "python_version >= '3.8'", - "version": "==3.7.2" - }, "mypy-extensions": { "hashes": [ "sha256:4392f6c0eb8a5668a69e23d168ffa70f0be9ccfd32b5cc2d26a34ae5b844552d", @@ -584,22 +369,6 @@ "index": "pypi", "version": "==3.1.7" }, - "pyparsing": { - "hashes": [ - "sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb", - "sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc" - ], - "markers": "python_full_version >= '3.6.8'", - "version": "==3.0.9" - }, - "python-dateutil": { - "hashes": [ - "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86", - "sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9" - ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.8.2" - }, "pyyaml": { "hashes": [ "sha256:062582fca9fabdd2c8b54a3ef1c978d786e0f6b3a1510e0ac93ef59e0ddae2bc", @@ -733,14 +502,6 @@ "markers": "python_version >= '3.7'", "version": "==2.0.1" }, - "six": { - "hashes": [ - "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926", - "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254" - ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==1.16.0" - }, "typing-extensions": { "hashes": [ "sha256:440d5dd3af93b060174bf433bccd69b0babc3b15b1a8dca43789fd7f61514b36", @@ -851,23 +612,76 @@ "markers": "python_version >= '3.6'", "version": "==0.1.4" }, - "debugpy": { + "contourpy": { "hashes": [ - "sha256:038c51268367c9c935905a90b1c2d2dbfe304037c27ba9d19fe7409f8cdc710c", - "sha256:1093a5c541af079c13ac8c70ab8b24d1d35c8cacb676306cf11e57f699c02926", - "sha256:3370ef1b9951d15799ef7af41f8174194f3482ee689988379763ef61a5456426", - "sha256:38651c3639a4e8bbf0ca7e52d799f6abd07d622a193c406be375da4d510d968d", - "sha256:3de5d0f97c425dc49bce4293df6a04494309eedadd2b52c22e58d95107e178d9", - "sha256:4b9eba71c290852f959d2cf8a03af28afd3ca639ad374d393d53d367f7f685b2", - "sha256:65b28435a17cba4c09e739621173ff90c515f7b9e8ea469b92e3c28ef8e5cdfb", - "sha256:72f5d2ecead8125cf669e62784ef1e6300f4067b0f14d9f95ee00ae06fc7c4f7", - "sha256:85969d864c45f70c3996067cfa76a319bae749b04171f2cdeceebe4add316155", - "sha256:890f7ab9a683886a0f185786ffbda3b46495c4b929dab083b8c79d6825832a52", - "sha256:903bd61d5eb433b6c25b48eae5e23821d4c1a19e25c9610205f5aeaccae64e32", - "sha256:92b6dae8bfbd497c90596bbb69089acf7954164aea3228a99d7e43e5267f5b36", - "sha256:973a97ed3b434eab0f792719a484566c35328196540676685c975651266fccf9", - "sha256:d16882030860081e7dd5aa619f30dec3c2f9a421e69861125f83cc372c94e57d", - "sha256:d4ac7a4dba28801d184b7fc0e024da2635ca87d8b0a825c6087bb5168e3c0d28", + "sha256:052cc634bf903c604ef1a00a5aa093c54f81a2612faedaa43295809ffdde885e", + "sha256:084eaa568400cfaf7179b847ac871582199b1b44d5699198e9602ecbbb5f6104", + "sha256:0b6616375d7de55797d7a66ee7d087efe27f03d336c27cf1f32c02b8c1a5ac70", + "sha256:0b7b04ed0961647691cfe5d82115dd072af7ce8846d31a5fac6c142dcce8b882", + "sha256:143dde50520a9f90e4a2703f367cf8ec96a73042b72e68fcd184e1279962eb6f", + "sha256:17cfaf5ec9862bc93af1ec1f302457371c34e688fbd381f4035a06cd47324f48", + "sha256:181cbace49874f4358e2929aaf7ba84006acb76694102e88dd15af861996c16e", + "sha256:189ceb1525eb0655ab8487a9a9c41f42a73ba52d6789754788d1883fb06b2d8a", + "sha256:18a64814ae7bce73925131381603fff0116e2df25230dfc80d6d690aa6e20b37", + "sha256:1f0cbd657e9bde94cd0e33aa7df94fb73c1ab7799378d3b3f902eb8eb2e04a3a", + "sha256:1f795597073b09d631782e7245016a4323cf1cf0b4e06eef7ea6627e06a37ff2", + "sha256:25ae46595e22f93592d39a7eac3d638cda552c3e1160255258b695f7b58e5655", + "sha256:27bc79200c742f9746d7dd51a734ee326a292d77e7d94c8af6e08d1e6c15d545", + "sha256:2b836d22bd2c7bb2700348e4521b25e077255ebb6ab68e351ab5aa91ca27e027", + "sha256:30f511c05fab7f12e0b1b7730ebdc2ec8deedcfb505bc27eb570ff47c51a8f15", + "sha256:317267d915490d1e84577924bd61ba71bf8681a30e0d6c545f577363157e5e94", + "sha256:397b0ac8a12880412da3551a8cb5a187d3298a72802b45a3bd1805e204ad8439", + "sha256:438ba416d02f82b692e371858143970ed2eb6337d9cdbbede0d8ad9f3d7dd17d", + "sha256:53cc3a40635abedbec7f1bde60f8c189c49e84ac180c665f2cd7c162cc454baa", + "sha256:5d123a5bc63cd34c27ff9c7ac1cd978909e9c71da12e05be0231c608048bb2ae", + "sha256:62013a2cf68abc80dadfd2307299bfa8f5aa0dcaec5b2954caeb5fa094171103", + "sha256:89f06eff3ce2f4b3eb24c1055a26981bffe4e7264acd86f15b97e40530b794bc", + "sha256:90c81f22b4f572f8a2110b0b741bb64e5a6427e0a198b2cdc1fbaf85f352a3aa", + "sha256:911ff4fd53e26b019f898f32db0d4956c9d227d51338fb3b03ec72ff0084ee5f", + "sha256:9382a1c0bc46230fb881c36229bfa23d8c303b889b788b939365578d762b5c18", + "sha256:9f2931ed4741f98f74b410b16e5213f71dcccee67518970c42f64153ea9313b9", + "sha256:a67259c2b493b00e5a4d0f7bfae51fb4b3371395e47d079a4446e9b0f4d70e76", + "sha256:a698c6a7a432789e587168573a864a7ea374c6be8d4f31f9d87c001d5a843493", + "sha256:bc00bb4225d57bff7ebb634646c0ee2a1298402ec10a5fe7af79df9a51c1bfd9", + "sha256:bcb41692aa09aeb19c7c213411854402f29f6613845ad2453d30bf421fe68fed", + "sha256:d4f26b25b4f86087e7d75e63212756c38546e70f2a92d2be44f80114826e1cd4", + "sha256:d551f3a442655f3dcc1285723f9acd646ca5858834efeab4598d706206b09c9f", + "sha256:dffcc2ddec1782dd2f2ce1ef16f070861af4fb78c69862ce0aab801495dda6a3", + "sha256:e53046c3863828d21d531cc3b53786e6580eb1ba02477e8681009b6aa0870b21", + "sha256:e5cec36c5090e75a9ac9dbd0ff4a8cf7cecd60f1b6dc23a374c7d980a1cd710e", + "sha256:e7a117ce7df5a938fe035cad481b0189049e8d92433b4b33aa7fc609344aafa1", + "sha256:e94bef2580e25b5fdb183bf98a2faa2adc5b638736b2c0a4da98691da641316a", + "sha256:ed614aea8462735e7d70141374bd7650afd1c3f3cb0c2dbbcbe44e14331bf002", + "sha256:fb3b7d9e6243bfa1efb93ccfe64ec610d85cfe5aec2c25f97fbbd2e58b531256" + ], + "markers": "python_version >= '3.8'", + "version": "==1.1.0" + }, + "cycler": { + "hashes": [ + "sha256:3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3", + "sha256:9c87405839a19696e837b3b818fed3f5f69f16f1eec1a1ad77e043dcea9c772f" + ], + "markers": "python_version >= '3.6'", + "version": "==0.11.0" + }, + "debugpy": { + "hashes": [ + "sha256:038c51268367c9c935905a90b1c2d2dbfe304037c27ba9d19fe7409f8cdc710c", + "sha256:1093a5c541af079c13ac8c70ab8b24d1d35c8cacb676306cf11e57f699c02926", + "sha256:3370ef1b9951d15799ef7af41f8174194f3482ee689988379763ef61a5456426", + "sha256:38651c3639a4e8bbf0ca7e52d799f6abd07d622a193c406be375da4d510d968d", + "sha256:3de5d0f97c425dc49bce4293df6a04494309eedadd2b52c22e58d95107e178d9", + "sha256:4b9eba71c290852f959d2cf8a03af28afd3ca639ad374d393d53d367f7f685b2", + "sha256:65b28435a17cba4c09e739621173ff90c515f7b9e8ea469b92e3c28ef8e5cdfb", + "sha256:72f5d2ecead8125cf669e62784ef1e6300f4067b0f14d9f95ee00ae06fc7c4f7", + "sha256:85969d864c45f70c3996067cfa76a319bae749b04171f2cdeceebe4add316155", + "sha256:890f7ab9a683886a0f185786ffbda3b46495c4b929dab083b8c79d6825832a52", + "sha256:903bd61d5eb433b6c25b48eae5e23821d4c1a19e25c9610205f5aeaccae64e32", + "sha256:92b6dae8bfbd497c90596bbb69089acf7954164aea3228a99d7e43e5267f5b36", + "sha256:973a97ed3b434eab0f792719a484566c35328196540676685c975651266fccf9", + "sha256:d16882030860081e7dd5aa619f30dec3c2f9a421e69861125f83cc372c94e57d", + "sha256:d4ac7a4dba28801d184b7fc0e024da2635ca87d8b0a825c6087bb5168e3c0d28", "sha256:eea8d8cfb9965ac41b99a61f8e755a8f50e9a20330938ad8271530210f54e09c", "sha256:f0851403030f3975d6e2eaa4abf73232ab90b98f041e3c09ba33be2beda43fcf", "sha256:fe87ec0182ef624855d05e6ed7e0b7cb1359d2ffa2a925f8ec2d22e98b75d0ca" @@ -907,6 +721,46 @@ "markers": "python_full_version >= '3.8.1'", "version": "==6.1.0" }, + "fonttools": { + "hashes": [ + "sha256:0eb79a2da5eb6457a6f8ab904838454accc7d4cccdaff1fd2bd3a0679ea33d64", + "sha256:113337c2d29665839b7d90b39f99b3cac731f72a0eda9306165a305c7c31d341", + "sha256:12a7c247d1b946829bfa2f331107a629ea77dc5391dfd34fdcd78efa61f354ca", + "sha256:179737095eb98332a2744e8f12037b2977f22948cf23ff96656928923ddf560a", + "sha256:19b7db825c8adee96fac0692e6e1ecd858cae9affb3b4812cdb9d934a898b29e", + "sha256:37983b6bdab42c501202500a2be3a572f50d4efe3237e0686ee9d5f794d76b35", + "sha256:3a35981d90feebeaef05e46e33e6b9e5b5e618504672ca9cd0ff96b171e4bfff", + "sha256:46a0ec8adbc6ff13494eb0c9c2e643b6f009ce7320cf640de106fb614e4d4360", + "sha256:4aa79366e442dbca6e2c8595645a3a605d9eeabdb7a094d745ed6106816bef5d", + "sha256:515607ec756d7865f23070682622c49d922901943697871fc292277cf1e71967", + "sha256:53eb5091ddc8b1199330bb7b4a8a2e7995ad5d43376cadce84523d8223ef3136", + "sha256:5d18fc642fd0ac29236ff88ecfccff229ec0386090a839dd3f1162e9a7944a40", + "sha256:5fb289b7a815638a7613d46bcf324c9106804725b2bb8ad913c12b6958ffc4ec", + "sha256:62f481ac772fd68901573956231aea3e4b1ad87b9b1089a61613a91e2b50bb9b", + "sha256:689508b918332fb40ce117131633647731d098b1b10d092234aa959b4251add5", + "sha256:68a02bbe020dc22ee0540e040117535f06df9358106d3775e8817d826047f3fd", + "sha256:6ed2662a3d9c832afa36405f8748c250be94ae5dfc5283d668308391f2102861", + "sha256:7286aed4ea271df9eab8d7a9b29e507094b51397812f7ce051ecd77915a6e26b", + "sha256:7cc7d685b8eeca7ae69dc6416833fbfea61660684b7089bca666067cb2937dcf", + "sha256:8708b98c278012ad267ee8a7433baeb809948855e81922878118464b274c909d", + "sha256:9398f244e28e0596e2ee6024f808b06060109e33ed38dcc9bded452fd9bbb853", + "sha256:9e36344e48af3e3bde867a1ca54f97c308735dd8697005c2d24a86054a114a71", + "sha256:a398bdadb055f8de69f62b0fc70625f7cbdab436bbb31eef5816e28cab083ee8", + "sha256:acb47f6f8680de24c1ab65ebde39dd035768e2a9b571a07c7b8da95f6c8815fd", + "sha256:be24fcb80493b2c94eae21df70017351851652a37de514de553435b256b2f249", + "sha256:c391cd5af88aacaf41dd7cfb96eeedfad297b5899a39e12f4c2c3706d0a3329d", + "sha256:c95b0724a6deea2c8c5d3222191783ced0a2f09bd6d33f93e563f6f1a4b3b3a4", + "sha256:c9b1ce7a45978b821a06d375b83763b27a3a5e8a2e4570b3065abad240a18760", + "sha256:db372213d39fa33af667c2aa586a0c1235e88e9c850f5dd5c8e1f17515861868", + "sha256:db55cbaea02a20b49fefbd8e9d62bd481aaabe1f2301dabc575acc6b358874fa", + "sha256:ed1a13a27f59d1fc1920394a7f596792e9d546c9ca5a044419dca70c37815d7c", + "sha256:f2b82f46917d8722e6b5eafeefb4fb585d23babd15d8246c664cd88a5bddd19c", + "sha256:f2f806990160d1ce42d287aa419df3ffc42dfefe60d473695fb048355fe0c6a0", + "sha256:f720fa82a11c0f9042376fd509b5ed88dab7e3cd602eee63a1af08883b37342b" + ], + "markers": "python_version >= '3.8'", + "version": "==4.42.1" + }, "iniconfig": { "hashes": [ "sha256:2d91e135bf72d31a410b17c16da610a82cb55f6b0477d1a902134b24a455b8b3", @@ -965,6 +819,128 @@ "markers": "python_version >= '3.8'", "version": "==5.3.1" }, + "kiwisolver": { + "hashes": [ + "sha256:02f79693ec433cb4b5f51694e8477ae83b3205768a6fb48ffba60549080e295b", + "sha256:03baab2d6b4a54ddbb43bba1a3a2d1627e82d205c5cf8f4c924dc49284b87166", + "sha256:1041feb4cda8708ce73bb4dcb9ce1ccf49d553bf87c3954bdfa46f0c3f77252c", + "sha256:10ee06759482c78bdb864f4109886dff7b8a56529bc1609d4f1112b93fe6423c", + "sha256:1d1573129aa0fd901076e2bfb4275a35f5b7aa60fbfb984499d661ec950320b0", + "sha256:283dffbf061a4ec60391d51e6155e372a1f7a4f5b15d59c8505339454f8989e4", + "sha256:28bc5b299f48150b5f822ce68624e445040595a4ac3d59251703779836eceff9", + "sha256:2a66fdfb34e05b705620dd567f5a03f239a088d5a3f321e7b6ac3239d22aa286", + "sha256:2e307eb9bd99801f82789b44bb45e9f541961831c7311521b13a6c85afc09767", + "sha256:2e407cb4bd5a13984a6c2c0fe1845e4e41e96f183e5e5cd4d77a857d9693494c", + "sha256:2f5e60fabb7343a836360c4f0919b8cd0d6dbf08ad2ca6b9cf90bf0c76a3c4f6", + "sha256:36dafec3d6d6088d34e2de6b85f9d8e2324eb734162fba59d2ba9ed7a2043d5b", + "sha256:3fe20f63c9ecee44560d0e7f116b3a747a5d7203376abeea292ab3152334d004", + "sha256:41dae968a94b1ef1897cb322b39360a0812661dba7c682aa45098eb8e193dbdf", + "sha256:4bd472dbe5e136f96a4b18f295d159d7f26fd399136f5b17b08c4e5f498cd494", + "sha256:4ea39b0ccc4f5d803e3337dd46bcce60b702be4d86fd0b3d7531ef10fd99a1ac", + "sha256:5853eb494c71e267912275e5586fe281444eb5e722de4e131cddf9d442615626", + "sha256:5bce61af018b0cb2055e0e72e7d65290d822d3feee430b7b8203d8a855e78766", + "sha256:6295ecd49304dcf3bfbfa45d9a081c96509e95f4b9d0eb7ee4ec0530c4a96514", + "sha256:62ac9cc684da4cf1778d07a89bf5f81b35834cb96ca523d3a7fb32509380cbf6", + "sha256:70e7c2e7b750585569564e2e5ca9845acfaa5da56ac46df68414f29fea97be9f", + "sha256:7577c1987baa3adc4b3c62c33bd1118c3ef5c8ddef36f0f2c950ae0b199e100d", + "sha256:75facbe9606748f43428fc91a43edb46c7ff68889b91fa31f53b58894503a191", + "sha256:787518a6789009c159453da4d6b683f468ef7a65bbde796bcea803ccf191058d", + "sha256:78d6601aed50c74e0ef02f4204da1816147a6d3fbdc8b3872d263338a9052c51", + "sha256:7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f", + "sha256:81e38381b782cc7e1e46c4e14cd997ee6040768101aefc8fa3c24a4cc58e98f8", + "sha256:841293b17ad704d70c578f1f0013c890e219952169ce8a24ebc063eecf775454", + "sha256:872b8ca05c40d309ed13eb2e582cab0c5a05e81e987ab9c521bf05ad1d5cf5cb", + "sha256:877272cf6b4b7e94c9614f9b10140e198d2186363728ed0f701c6eee1baec1da", + "sha256:8c808594c88a025d4e322d5bb549282c93c8e1ba71b790f539567932722d7bd8", + "sha256:8ed58b8acf29798b036d347791141767ccf65eee7f26bde03a71c944449e53de", + "sha256:91672bacaa030f92fc2f43b620d7b337fd9a5af28b0d6ed3f77afc43c4a64b5a", + "sha256:968f44fdbf6dd757d12920d63b566eeb4d5b395fd2d00d29d7ef00a00582aac9", + "sha256:9f85003f5dfa867e86d53fac6f7e6f30c045673fa27b603c397753bebadc3008", + "sha256:a553dadda40fef6bfa1456dc4be49b113aa92c2a9a9e8711e955618cd69622e3", + "sha256:a68b62a02953b9841730db7797422f983935aeefceb1679f0fc85cbfbd311c32", + "sha256:abbe9fa13da955feb8202e215c4018f4bb57469b1b78c7a4c5c7b93001699938", + "sha256:ad881edc7ccb9d65b0224f4e4d05a1e85cf62d73aab798943df6d48ab0cd79a1", + "sha256:b1792d939ec70abe76f5054d3f36ed5656021dcad1322d1cc996d4e54165cef9", + "sha256:b428ef021242344340460fa4c9185d0b1f66fbdbfecc6c63eff4b7c29fad429d", + "sha256:b533558eae785e33e8c148a8d9921692a9fe5aa516efbdff8606e7d87b9d5824", + "sha256:ba59c92039ec0a66103b1d5fe588fa546373587a7d68f5c96f743c3396afc04b", + "sha256:bc8d3bd6c72b2dd9decf16ce70e20abcb3274ba01b4e1c96031e0c4067d1e7cd", + "sha256:bc9db8a3efb3e403e4ecc6cd9489ea2bac94244f80c78e27c31dcc00d2790ac2", + "sha256:bf7d9fce9bcc4752ca4a1b80aabd38f6d19009ea5cbda0e0856983cf6d0023f5", + "sha256:c2dbb44c3f7e6c4d3487b31037b1bdbf424d97687c1747ce4ff2895795c9bf69", + "sha256:c79ebe8f3676a4c6630fd3f777f3cfecf9289666c84e775a67d1d358578dc2e3", + "sha256:c97528e64cb9ebeff9701e7938653a9951922f2a38bd847787d4a8e498cc83ae", + "sha256:d0611a0a2a518464c05ddd5a3a1a0e856ccc10e67079bb17f265ad19ab3c7597", + "sha256:d06adcfa62a4431d404c31216f0f8ac97397d799cd53800e9d3efc2fbb3cf14e", + "sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955", + "sha256:d5b61785a9ce44e5a4b880272baa7cf6c8f48a5180c3e81c59553ba0cb0821ca", + "sha256:da152d8cdcab0e56e4f45eb08b9aea6455845ec83172092f09b0e077ece2cf7a", + "sha256:da7e547706e69e45d95e116e6939488d62174e033b763ab1496b4c29b76fabea", + "sha256:db5283d90da4174865d520e7366801a93777201e91e79bacbac6e6927cbceede", + "sha256:db608a6757adabb32f1cfe6066e39b3706d8c3aa69bbc353a5b61edad36a5cb4", + "sha256:e0ea21f66820452a3f5d1655f8704a60d66ba1191359b96541eaf457710a5fc6", + "sha256:e7da3fec7408813a7cebc9e4ec55afed2d0fd65c4754bc376bf03498d4e92686", + "sha256:e92a513161077b53447160b9bd8f522edfbed4bd9759e4c18ab05d7ef7e49408", + "sha256:ecb1fa0db7bf4cff9dac752abb19505a233c7f16684c5826d1f11ebd9472b871", + "sha256:efda5fc8cc1c61e4f639b8067d118e742b812c930f708e6667a5ce0d13499e29", + "sha256:f0a1dbdb5ecbef0d34eb77e56fcb3e95bbd7e50835d9782a45df81cc46949750", + "sha256:f0a71d85ecdd570ded8ac3d1c0f480842f49a40beb423bb8014539a9f32a5897", + "sha256:f4f270de01dd3e129a72efad823da90cc4d6aafb64c410c9033aba70db9f1ff0", + "sha256:f6cb459eea32a4e2cf18ba5fcece2dbdf496384413bc1bae15583f19e567f3b2", + "sha256:f8ad8285b01b0d4695102546b342b493b3ccc6781fc28c8c6a1bb63e95d22f09", + "sha256:f9f39e2f049db33a908319cf46624a569b36983c7c78318e9726a4cb8923b26c" + ], + "markers": "python_version >= '3.7'", + "version": "==1.4.4" + }, + "matplotlib": { + "hashes": [ + "sha256:070f8dddd1f5939e60aacb8fa08f19551f4b0140fab16a3669d5cd6e9cb28fc8", + "sha256:0c3cca3e842b11b55b52c6fb8bd6a4088693829acbfcdb3e815fa9b7d5c92c1b", + "sha256:0f506a1776ee94f9e131af1ac6efa6e5bc7cb606a3e389b0ccb6e657f60bb676", + "sha256:12f01b92ecd518e0697da4d97d163b2b3aa55eb3eb4e2c98235b3396d7dad55f", + "sha256:152ee0b569a37630d8628534c628456b28686e085d51394da6b71ef84c4da201", + "sha256:1c308b255efb9b06b23874236ec0f10f026673ad6515f602027cc8ac7805352d", + "sha256:1cd120fca3407a225168238b790bd5c528f0fafde6172b140a2f3ab7a4ea63e9", + "sha256:20f844d6be031948148ba49605c8b96dfe7d3711d1b63592830d650622458c11", + "sha256:23fb1750934e5f0128f9423db27c474aa32534cec21f7b2153262b066a581fd1", + "sha256:2699f7e73a76d4c110f4f25be9d2496d6ab4f17345307738557d345f099e07de", + "sha256:26bede320d77e469fdf1bde212de0ec889169b04f7f1179b8930d66f82b30cbc", + "sha256:2ecb5be2b2815431c81dc115667e33da0f5a1bcf6143980d180d09a717c4a12e", + "sha256:2f8e4a49493add46ad4a8c92f63e19d548b2b6ebbed75c6b4c7f46f57d36cdd1", + "sha256:305e3da477dc8607336ba10bac96986d6308d614706cae2efe7d3ffa60465b24", + "sha256:30e1409b857aa8a747c5d4f85f63a79e479835f8dffc52992ac1f3f25837b544", + "sha256:318c89edde72ff95d8df67d82aca03861240512994a597a435a1011ba18dbc7f", + "sha256:35d74ebdb3f71f112b36c2629cf32323adfbf42679e2751252acd468f5001c07", + "sha256:50e0a55ec74bf2d7a0ebf50ac580a209582c2dd0f7ab51bc270f1b4a0027454e", + "sha256:5dea00b62d28654b71ca92463656d80646675628d0828e08a5f3b57e12869e13", + "sha256:60c521e21031632aa0d87ca5ba0c1c05f3daacadb34c093585a0be6780f698e4", + "sha256:6515e878f91894c2e4340d81f0911857998ccaf04dbc1bba781e3d89cbf70608", + "sha256:6d2ff3c984b8a569bc1383cd468fc06b70d7b59d5c2854ca39f1436ae8394117", + "sha256:71667eb2ccca4c3537d9414b1bc00554cb7f91527c17ee4ec38027201f8f1603", + "sha256:717157e61b3a71d3d26ad4e1770dc85156c9af435659a25ee6407dc866cb258d", + "sha256:71f7a8c6b124e904db550f5b9fe483d28b896d4135e45c4ea381ad3b8a0e3256", + "sha256:936bba394682049919dda062d33435b3be211dc3dcaa011e09634f060ec878b2", + "sha256:a1733b8e84e7e40a9853e505fe68cc54339f97273bdfe6f3ed980095f769ddc7", + "sha256:a2c1590b90aa7bd741b54c62b78de05d4186271e34e2377e0289d943b3522273", + "sha256:a7e28d6396563955f7af437894a36bf2b279462239a41028323e04b85179058b", + "sha256:a8035ba590658bae7562786c9cc6ea1a84aa49d3afab157e414c9e2ea74f496d", + "sha256:a8cdb91dddb04436bd2f098b8fdf4b81352e68cf4d2c6756fcc414791076569b", + "sha256:ac60daa1dc83e8821eed155796b0f7888b6b916cf61d620a4ddd8200ac70cd64", + "sha256:af4860132c8c05261a5f5f8467f1b269bf1c7c23902d75f2be57c4a7f2394b3e", + "sha256:bc221ffbc2150458b1cd71cdd9ddd5bb37962b036e41b8be258280b5b01da1dd", + "sha256:ce55289d5659b5b12b3db4dc9b7075b70cef5631e56530f14b2945e8836f2d20", + "sha256:d9881356dc48e58910c53af82b57183879129fa30492be69058c5b0d9fddf391", + "sha256:dbcf59334ff645e6a67cd5f78b4b2cdb76384cdf587fa0d2dc85f634a72e1a3e", + "sha256:ebf577c7a6744e9e1bd3fee45fc74a02710b214f94e2bde344912d85e0c9af7c", + "sha256:f081c03f413f59390a80b3e351cc2b2ea0205839714dbc364519bcf51f4b56ca", + "sha256:fdbb46fad4fb47443b5b8ac76904b2e7a66556844f33370861b4788db0f8816a", + "sha256:fdcd28360dbb6203fb5219b1a5658df226ac9bebc2542a9e8f457de959d713d0" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==3.7.2" + }, "matplotlib-inline": { "hashes": [ "sha256:f1f41aab5328aa5aaea9b16d083b128102f8712542f819fe7e6a420ff581b311", @@ -997,6 +973,41 @@ "markers": "python_version >= '3.5'", "version": "==1.5.7" }, + "numpy": { + "hashes": [ + "sha256:04640dab83f7c6c85abf9cd729c5b65f1ebd0ccf9de90b270cd61935eef0197f", + "sha256:1452241c290f3e2a312c137a9999cdbf63f78864d63c79039bda65ee86943f61", + "sha256:222e40d0e2548690405b0b3c7b21d1169117391c2e82c378467ef9ab4c8f0da7", + "sha256:2541312fbf09977f3b3ad449c4e5f4bb55d0dbf79226d7724211acc905049400", + "sha256:31f13e25b4e304632a4619d0e0777662c2ffea99fcae2029556b17d8ff958aef", + "sha256:4602244f345453db537be5314d3983dbf5834a9701b7723ec28923e2889e0bb2", + "sha256:4979217d7de511a8d57f4b4b5b2b965f707768440c17cb70fbf254c4b225238d", + "sha256:4c21decb6ea94057331e111a5bed9a79d335658c27ce2adb580fb4d54f2ad9bc", + "sha256:6620c0acd41dbcb368610bb2f4d83145674040025e5536954782467100aa8835", + "sha256:692f2e0f55794943c5bfff12b3f56f99af76f902fc47487bdfe97856de51a706", + "sha256:7215847ce88a85ce39baf9e89070cb860c98fdddacbaa6c0da3ffb31b3350bd5", + "sha256:79fc682a374c4a8ed08b331bef9c5f582585d1048fa6d80bc6c35bc384eee9b4", + "sha256:7ffe43c74893dbf38c2b0a1f5428760a1a9c98285553c89e12d70a96a7f3a4d6", + "sha256:80f5e3a4e498641401868df4208b74581206afbee7cf7b8329daae82676d9463", + "sha256:95f7ac6540e95bc440ad77f56e520da5bf877f87dca58bd095288dce8940532a", + "sha256:9667575fb6d13c95f1b36aca12c5ee3356bf001b714fc354eb5465ce1609e62f", + "sha256:a5425b114831d1e77e4b5d812b69d11d962e104095a5b9c3b641a218abcc050e", + "sha256:b4bea75e47d9586d31e892a7401f76e909712a0fd510f58f5337bea9572c571e", + "sha256:b7b1fc9864d7d39e28f41d089bfd6353cb5f27ecd9905348c24187a768c79694", + "sha256:befe2bf740fd8373cf56149a5c23a0f601e82869598d41f8e188a0e9869926f8", + "sha256:c0bfb52d2169d58c1cdb8cc1f16989101639b34c7d3ce60ed70b19c63eba0b64", + "sha256:d11efb4dbecbdf22508d55e48d9c8384db795e1b7b51ea735289ff96613ff74d", + "sha256:dd80e219fd4c71fc3699fc1dadac5dcf4fd882bfc6f7ec53d30fa197b8ee22dc", + "sha256:e2926dac25b313635e4d6cf4dc4e51c8c0ebfed60b801c799ffc4c32bf3d1254", + "sha256:e98f220aa76ca2a977fe435f5b04d7b3470c0a2e6312907b37ba6068f26787f2", + "sha256:ed094d4f0c177b1b8e7aa9cba7d6ceed51c0e569a5318ac0ca9a090680a6a1b1", + "sha256:f136bab9c2cfd8da131132c2cf6cc27331dd6fae65f95f69dcd4ae3c3639c810", + "sha256:f3a86ed21e4f87050382c7bc96571755193c4c1392490744ac73d660e8f564a9" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==1.24.4" + }, "packaging": { "hashes": [ "sha256:994793af429502c4ea2ebf6bf664629d07c1a9fe974af92966e4b8d2df7edc61", @@ -1028,6 +1039,69 @@ ], "version": "==0.7.5" }, + "pillow": { + "hashes": [ + "sha256:00e65f5e822decd501e374b0650146063fbb30a7264b4d2744bdd7b913e0cab5", + "sha256:040586f7d37b34547153fa383f7f9aed68b738992380ac911447bb78f2abe530", + "sha256:0b6eb5502f45a60a3f411c63187db83a3d3107887ad0d036c13ce836f8a36f1d", + "sha256:1ce91b6ec08d866b14413d3f0bbdea7e24dfdc8e59f562bb77bc3fe60b6144ca", + "sha256:1f62406a884ae75fb2f818694469519fb685cc7eaff05d3451a9ebe55c646891", + "sha256:22c10cc517668d44b211717fd9775799ccec4124b9a7f7b3635fc5386e584992", + "sha256:3400aae60685b06bb96f99a21e1ada7bc7a413d5f49bce739828ecd9391bb8f7", + "sha256:349930d6e9c685c089284b013478d6f76e3a534e36ddfa912cde493f235372f3", + "sha256:368ab3dfb5f49e312231b6f27b8820c823652b7cd29cfbd34090565a015e99ba", + "sha256:38250a349b6b390ee6047a62c086d3817ac69022c127f8a5dc058c31ccef17f3", + "sha256:3a684105f7c32488f7153905a4e3015a3b6c7182e106fe3c37fbb5ef3e6994c3", + "sha256:3a82c40d706d9aa9734289740ce26460a11aeec2d9c79b7af87bb35f0073c12f", + "sha256:3b08d4cc24f471b2c8ca24ec060abf4bebc6b144cb89cba638c720546b1cf538", + "sha256:3ed64f9ca2f0a95411e88a4efbd7a29e5ce2cea36072c53dd9d26d9c76f753b3", + "sha256:3f07ea8d2f827d7d2a49ecf1639ec02d75ffd1b88dcc5b3a61bbb37a8759ad8d", + "sha256:520f2a520dc040512699f20fa1c363eed506e94248d71f85412b625026f6142c", + "sha256:5c6e3df6bdd396749bafd45314871b3d0af81ff935b2d188385e970052091017", + "sha256:608bfdee0d57cf297d32bcbb3c728dc1da0907519d1784962c5f0c68bb93e5a3", + "sha256:685ac03cc4ed5ebc15ad5c23bc555d68a87777586d970c2c3e216619a5476223", + "sha256:76de421f9c326da8f43d690110f0e79fe3ad1e54be811545d7d91898b4c8493e", + "sha256:76edb0a1fa2b4745fb0c99fb9fb98f8b180a1bbceb8be49b087e0b21867e77d3", + "sha256:7be600823e4c8631b74e4a0d38384c73f680e6105a7d3c6824fcf226c178c7e6", + "sha256:81ff539a12457809666fef6624684c008e00ff6bf455b4b89fd00a140eecd640", + "sha256:88af2003543cc40c80f6fca01411892ec52b11021b3dc22ec3bc9d5afd1c5334", + "sha256:8c11160913e3dd06c8ffdb5f233a4f254cb449f4dfc0f8f4549eda9e542c93d1", + "sha256:8f8182b523b2289f7c415f589118228d30ac8c355baa2f3194ced084dac2dbba", + "sha256:9211e7ad69d7c9401cfc0e23d49b69ca65ddd898976d660a2fa5904e3d7a9baa", + "sha256:92be919bbc9f7d09f7ae343c38f5bb21c973d2576c1d45600fce4b74bafa7ac0", + "sha256:9c82b5b3e043c7af0d95792d0d20ccf68f61a1fec6b3530e718b688422727396", + "sha256:9f7c16705f44e0504a3a2a14197c1f0b32a95731d251777dcb060aa83022cb2d", + "sha256:9fb218c8a12e51d7ead2a7c9e101a04982237d4855716af2e9499306728fb485", + "sha256:a74ba0c356aaa3bb8e3eb79606a87669e7ec6444be352870623025d75a14a2bf", + "sha256:b4f69b3700201b80bb82c3a97d5e9254084f6dd5fb5b16fc1a7b974260f89f43", + "sha256:bc2ec7c7b5d66b8ec9ce9f720dbb5fa4bace0f545acd34870eff4a369b44bf37", + "sha256:c189af0545965fa8d3b9613cfdb0cd37f9d71349e0f7750e1fd704648d475ed2", + "sha256:c1fbe7621c167ecaa38ad29643d77a9ce7311583761abf7836e1510c580bf3dd", + "sha256:c7cf14a27b0d6adfaebb3ae4153f1e516df54e47e42dcc073d7b3d76111a8d86", + "sha256:c9f72a021fbb792ce98306ffb0c348b3c9cb967dce0f12a49aa4c3d3fdefa967", + "sha256:cd25d2a9d2b36fcb318882481367956d2cf91329f6892fe5d385c346c0649629", + "sha256:ce543ed15570eedbb85df19b0a1a7314a9c8141a36ce089c0a894adbfccb4568", + "sha256:ce7b031a6fc11365970e6a5686d7ba8c63e4c1cf1ea143811acbb524295eabed", + "sha256:d35e3c8d9b1268cbf5d3670285feb3528f6680420eafe35cccc686b73c1e330f", + "sha256:d50b6aec14bc737742ca96e85d6d0a5f9bfbded018264b3b70ff9d8c33485551", + "sha256:d5d0dae4cfd56969d23d94dc8e89fb6a217be461c69090768227beb8ed28c0a3", + "sha256:d5db32e2a6ccbb3d34d87c87b432959e0db29755727afb37290e10f6e8e62614", + "sha256:d72e2ecc68a942e8cf9739619b7f408cc7b272b279b56b2c83c6123fcfa5cdff", + "sha256:d737a602fbd82afd892ca746392401b634e278cb65d55c4b7a8f48e9ef8d008d", + "sha256:d80cf684b541685fccdd84c485b31ce73fc5c9b5d7523bf1394ce134a60c6883", + "sha256:db24668940f82321e746773a4bc617bfac06ec831e5c88b643f91f122a785684", + "sha256:dbc02381779d412145331789b40cc7b11fdf449e5d94f6bc0b080db0a56ea3f0", + "sha256:dffe31a7f47b603318c609f378ebcd57f1554a3a6a8effbc59c3c69f804296de", + "sha256:edf4392b77bdc81f36e92d3a07a5cd072f90253197f4a52a55a8cec48a12483b", + "sha256:efe8c0681042536e0d06c11f48cebe759707c9e9abf880ee213541c5b46c5bf3", + "sha256:f31f9fdbfecb042d046f9d91270a0ba28368a723302786c0009ee9b9f1f60199", + "sha256:f88a0b92277de8e3ca715a0d79d68dc82807457dae3ab8699c758f07c20b3c51", + "sha256:faaf07ea35355b01a35cb442dd950d8f1bb5b040a7787791a535de13db15ed90" + ], + "index": "pypi", + "markers": "python_version >= '3.8'", + "version": "==10.0.0" + }, "platformdirs": { "hashes": [ "sha256:b45696dab2d7cc691a3226759c0d3b00c47c8b6e293d96f6436f733303f77f6d", @@ -1103,6 +1177,14 @@ "markers": "python_version >= '3.7'", "version": "==2.16.1" }, + "pyparsing": { + "hashes": [ + "sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb", + "sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc" + ], + "markers": "python_full_version >= '3.6.8'", + "version": "==3.0.9" + }, "pytest": { "hashes": [ "sha256:78bf16451a2eb8c7a2ea98e32dc119fd2aa758f1d5d66dbf0a59d69a3969df32", diff --git a/gym/f110_gym/envs/__init__.py b/gym/f110_gym/envs/__init__.py index e69de29b..7c5cddc6 100644 --- a/gym/f110_gym/envs/__init__.py +++ b/gym/f110_gym/envs/__init__.py @@ -0,0 +1 @@ +from .f110_env import F110Env \ No newline at end of file diff --git a/gym/f110_gym/envs/base_classes.py b/gym/f110_gym/envs/base_classes.py index a75afd0b..91d8c3bc 100644 --- a/gym/f110_gym/envs/base_classes.py +++ b/gym/f110_gym/envs/base_classes.py @@ -27,7 +27,7 @@ Author: Hongrui Zheng """ import numpy as np -from f110_gym.envs import DynamicModel +from f110_gym.envs.dynamic_models import DynamicModel from f110_gym.envs.action import CarAction from f110_gym.envs.collision_models import collision_multiple, get_vertices from f110_gym.envs.integrator import EulerIntegrator, IntegratorType diff --git a/gym/f110_gym/envs/f110_env.py b/gym/f110_gym/envs/f110_env.py index d5cfd8ac..1a14fb4e 100644 --- a/gym/f110_gym/envs/f110_env.py +++ b/gym/f110_gym/envs/f110_env.py @@ -32,7 +32,7 @@ import numpy as np # gl import pyglet -from f110_gym.envs import IntegratorType +from f110_gym.envs.integrator import IntegratorType from f110_gym.envs.action import (CarActionEnum, from_single_to_multi_action_space) # base classes diff --git a/requirements.txt b/requirements.txt deleted file mode 100644 index cbd0f662..00000000 --- a/requirements.txt +++ /dev/null @@ -1,70 +0,0 @@ --i https://pypi.org/simple -certifi==2023.7.22; python_version >= '3.6' -charset-normalizer==3.2.0; python_full_version >= '3.7.0' -cloudpickle==2.2.1; python_version >= '3.6' -contourpy==1.1.0; python_version >= '3.8' -cycler==0.11.0; python_version >= '3.6' -dataclasses-json==0.5.14; python_version < '3.13' and python_version >= '3.7' --e . -farama-notifications==0.0.4 -fonttools==4.42.1; python_version >= '3.8' -future==0.18.3; python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3' -gymnasium==0.29.1; python_version >= '3.8' -idna==3.4; python_version >= '3.5' -kiwisolver==1.4.4; python_version >= '3.7' -llvmlite==0.40.1; python_version >= '3.8' -marshmallow==3.20.1; python_version >= '3.8' -matplotlib==3.7.2; python_version >= '3.8' -mypy-extensions==1.0.0; python_version >= '3.5' -numba==0.57.1; python_version >= '3.8' -numpy==1.22.0; python_version >= '3.8' -packaging==23.1; python_version >= '3.7' -pillow==10.0.0; python_version >= '3.8' -pyglet==1.4.11 -pyopengl==3.1.7 -pyparsing==3.0.9; python_full_version >= '3.6.8' -python-dateutil==2.8.2; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' -pyyaml==6.0.1; python_version >= '3.6' -requests==2.31.0; python_version >= '3.7' -scipy==1.11.2; python_version < '3.13' and python_version >= '3.9' -six==1.16.0; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' -typing-extensions==4.7.1; python_version >= '3.7' -typing-inspect==0.9.0 -urllib3==2.0.4; python_version >= '3.7' -yamldataclassconfig==1.5.0; python_version >= '3.7' --i https://pypi.org/simple -certifi==2023.7.22; python_version >= '3.6' -charset-normalizer==3.2.0; python_full_version >= '3.7.0' -cloudpickle==2.2.1; python_version >= '3.6' -contourpy==1.1.0; python_version >= '3.8' -cycler==0.11.0; python_version >= '3.6' -dataclasses-json==0.5.14; python_version < '3.13' and python_version >= '3.7' --e . -farama-notifications==0.0.4 -fonttools==4.42.1; python_version >= '3.8' -future==0.18.3; python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3' -gymnasium==0.29.1; python_version >= '3.8' -idna==3.4; python_version >= '3.5' -kiwisolver==1.4.4; python_version >= '3.7' -llvmlite==0.40.1; python_version >= '3.8' -marshmallow==3.20.1; python_version >= '3.8' -matplotlib==3.7.2; python_version >= '3.8' -mypy-extensions==1.0.0; python_version >= '3.5' -numba==0.57.1; python_version >= '3.8' -numpy==1.24.4; python_version >= '3.8' -opencv-python==4.8.0.76; python_version >= '3.6' -packaging==23.1; python_version >= '3.7' -pillow==10.0.0; python_version >= '3.8' -pyglet==1.4.11 -pyopengl==3.1.7 -pyparsing==3.0.9; python_full_version >= '3.6.8' -python-dateutil==2.8.2; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' -pyyaml==6.0.1; python_version >= '3.6' -requests==2.31.0; python_version >= '3.7' -scipy==1.11.2; python_version < '3.13' and python_version >= '3.9' -shapely==2.0.1; python_version >= '3.7' -six==1.16.0; python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3' -typing-extensions==4.7.1; python_version >= '3.7' -typing-inspect==0.9.0 -urllib3==2.0.4; python_version >= '3.7' -yamldataclassconfig==1.5.0; python_version >= '3.7' diff --git a/setup.cfg b/setup.cfg index 259f3aee..6721ba54 100644 --- a/setup.cfg +++ b/setup.cfg @@ -1,4 +1,4 @@ -[pytest] +[tool:pytest] minversion = 6.0 addopts = -ra -q testpaths = diff --git a/setup.py b/setup.py index c51abdaf..8d7de462 100644 --- a/setup.py +++ b/setup.py @@ -18,5 +18,18 @@ "pyopengl", "yamldataclassconfig", "requests", + "shapely", + "opencv-python", ], + extras_require={ + 'dev': [ + 'pytest', + 'flake8', + 'black', + 'ipykernel', + 'isort', + 'autoflake', + 'matplotlib' + ] + } ) diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index b3957d1e..21fae8c9 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -23,7 +23,7 @@ import unittest import numpy as np -from f110_gym.envs import vehicle_dynamics_ks, vehicle_dynamics_st +from f110_gym.envs.dynamic_models import vehicle_dynamics_ks, vehicle_dynamics_st def func_KS( diff --git a/tests/test_scan_sim.py b/tests/test_scan_sim.py index b41345c9..a97599c0 100644 --- a/tests/test_scan_sim.py +++ b/tests/test_scan_sim.py @@ -29,7 +29,7 @@ import unittest import numpy as np -from f110_gym.envs import ScanSimulator2D +from f110_gym.envs.laser_models import ScanSimulator2D from numba import njit from scipy.ndimage import distance_transform_edt as edt From 20231d2126b28b8c6d3f52ceefaf4478ce557132 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 17:37:58 -0400 Subject: [PATCH 17/32] Fixing some numba bugs --- gym/f110_gym/envs/dynamic_models.py | 1 + 1 file changed, 1 insertion(+) diff --git a/gym/f110_gym/envs/dynamic_models.py b/gym/f110_gym/envs/dynamic_models.py index 0ca1af3d..0c996f5f 100644 --- a/gym/f110_gym/envs/dynamic_models.py +++ b/gym/f110_gym/envs/dynamic_models.py @@ -77,6 +77,7 @@ def f_dynamics(self): raise ValueError(f"Unknown model type {self}") +@njit(cache=True) def accl_constraints(vel, accl, v_switch, a_max, v_min, v_max): """ Acceleration constraints, adjusts the acceleration based on constraints From 6b68e7e71a03d00625292f0ce90aa8d4dca5052d Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 17:42:48 -0400 Subject: [PATCH 18/32] Fixed temp file access on windows. Now platform-agnostic. --- gym/f110_gym/envs/track.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/gym/f110_gym/envs/track.py b/gym/f110_gym/envs/track.py index b8bbb6d2..6f50ecb7 100644 --- a/gym/f110_gym/envs/track.py +++ b/gym/f110_gym/envs/track.py @@ -2,6 +2,7 @@ import tarfile from dataclasses import dataclass from typing import Tuple +import tempfile import numpy as np import requests @@ -135,13 +136,15 @@ def find_track_dir(track_name): tracks_r = requests.get(url=tracks_url, allow_redirects=True) if tracks_r.status_code == 404: raise FileNotFoundError(f"No maps exists for {track_name}.") + + tempdir = tempfile.gettempdir() - with open("/tmp/" + track_name + ".tar.xz", "wb") as f: + with open(tempdir + track_name + ".tar.xz", "wb") as f: f.write(tracks_r.content) # extract print("Extracting Files for: " + track_name) - tracks_file = tarfile.open("/tmp/" + track_name + ".tar.xz") + tracks_file = tarfile.open(tempdir + track_name + ".tar.xz") tracks_file.extractall(map_dir) tracks_file.close() From 71bbf083a8325c535e34609177cbdbc2da2dbaba Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 17:48:46 -0400 Subject: [PATCH 19/32] Fixed tests for track directory --- tests/test_track.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_track.py b/tests/test_track.py index 0aeab271..37cfae07 100644 --- a/tests/test_track.py +++ b/tests/test_track.py @@ -54,7 +54,7 @@ def test_map_dir_structure(self): - [Trackname_raceline.csv] # raceline (optional) - [Trackname_centerline.csv] # centerline (optional) """ - mapdir = pathlib.Path(__file__).parent.parent / "maps" + mapdir = pathlib.Path(__file__).parent.parent / "gym"/ "f110_gym"/ "maps" for trackdir in mapdir.iterdir(): if trackdir.is_file(): continue From 910f9a7cc51b3cc776bc0f3035dc8c7d709ce1cd Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 17:55:32 -0400 Subject: [PATCH 20/32] Linting changes --- examples/random_trackgen.py | 2 +- gym/f110_gym/envs/__init__.py | 2 +- gym/f110_gym/envs/base_classes.py | 2 +- gym/f110_gym/envs/track.py | 2 +- tests/test_collision_checks.py | 5 ++--- tests/test_track.py | 2 +- 6 files changed, 7 insertions(+), 8 deletions(-) diff --git a/examples/random_trackgen.py b/examples/random_trackgen.py index 51eff46a..b9d17dbe 100644 --- a/examples/random_trackgen.py +++ b/examples/random_trackgen.py @@ -162,7 +162,7 @@ def create_track(): assert i1 != -1 assert i2 != -1 - track = track[i1 : i2 - 1] + track = track[i1: i2 - 1] first_beta = track[0][1] first_perp_x = math.cos(first_beta) first_perp_y = math.sin(first_beta) diff --git a/gym/f110_gym/envs/__init__.py b/gym/f110_gym/envs/__init__.py index 7c5cddc6..86fed2dc 100644 --- a/gym/f110_gym/envs/__init__.py +++ b/gym/f110_gym/envs/__init__.py @@ -1 +1 @@ -from .f110_env import F110Env \ No newline at end of file +from .f110_env import F110Env diff --git a/gym/f110_gym/envs/base_classes.py b/gym/f110_gym/envs/base_classes.py index 91d8c3bc..a03cbf98 100644 --- a/gym/f110_gym/envs/base_classes.py +++ b/gym/f110_gym/envs/base_classes.py @@ -512,7 +512,7 @@ def step(self, control_inputs): for i, agent in enumerate(self.agents): # update agent's information on other agents opp_poses = np.concatenate( - (self.agent_poses[0:i, :], self.agent_poses[i + 1 :, :]), axis=0 + (self.agent_poses[0:i, :], self.agent_poses[i + 1:, :]), axis=0 ) agent.update_opp_poses(opp_poses) diff --git a/gym/f110_gym/envs/track.py b/gym/f110_gym/envs/track.py index 6f50ecb7..710cd68d 100644 --- a/gym/f110_gym/envs/track.py +++ b/gym/f110_gym/envs/track.py @@ -136,7 +136,7 @@ def find_track_dir(track_name): tracks_r = requests.get(url=tracks_url, allow_redirects=True) if tracks_r.status_code == 404: raise FileNotFoundError(f"No maps exists for {track_name}.") - + tempdir = tempfile.gettempdir() with open(tempdir + track_name + ".tar.xz", "wb") as f: diff --git a/tests/test_collision_checks.py b/tests/test_collision_checks.py index 8e7434bf..08315a6c 100644 --- a/tests/test_collision_checks.py +++ b/tests/test_collision_checks.py @@ -26,6 +26,8 @@ Author: Hongrui Zheng """ +import unittest +import time import numpy as np from numba import njit @@ -248,9 +250,6 @@ def get_vertices(pose, length, width): Author: Hongrui Zheng """ -import time -import unittest - class CollisionTests(unittest.TestCase): def setUp(self): diff --git a/tests/test_track.py b/tests/test_track.py index 37cfae07..8c0d16be 100644 --- a/tests/test_track.py +++ b/tests/test_track.py @@ -54,7 +54,7 @@ def test_map_dir_structure(self): - [Trackname_raceline.csv] # raceline (optional) - [Trackname_centerline.csv] # centerline (optional) """ - mapdir = pathlib.Path(__file__).parent.parent / "gym"/ "f110_gym"/ "maps" + mapdir = pathlib.Path(__file__).parent.parent / "gym" / "f110_gym" / "maps" for trackdir in mapdir.iterdir(): if trackdir.is_file(): continue From 81f069c8b1d19f03bd17e1a539dec2b31b94d8f4 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:09:27 -0400 Subject: [PATCH 21/32] Fixed all linting errors. --- docs/conf.py | 3 ++- examples/random_trackgen.py | 2 +- examples/waypoint_follow.py | 2 +- gym/f110_gym/envs/__init__.py | 2 +- gym/f110_gym/envs/base_classes.py | 2 -- gym/f110_gym/envs/dynamic_models.py | 6 +----- gym/f110_gym/envs/f110_env_backup.py | 2 +- gym/f110_gym/envs/integrator.py | 2 +- gym/f110_gym/envs/laser_models.py | 8 ++++---- gym/f110_gym/envs/observation.py | 8 ++++---- gym/f110_gym/envs/rendering.py | 1 + setup.cfg | 2 +- tests/pyglet_test_.py | 1 + tests/pyglet_test_camera.py | 1 + tests/test_collision_checks.py | 2 +- tests/test_dynamics.py | 14 +++++++------- tests/test_observation.py | 2 +- tests/test_scan_sim.py | 8 ++++---- tests/test_track.py | 4 ++-- 19 files changed, 35 insertions(+), 37 deletions(-) diff --git a/docs/conf.py b/docs/conf.py index 9362d15b..c3decdd4 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,3 +1,4 @@ +# flake8: noqa import os import sphinx_rtd_theme @@ -7,7 +8,7 @@ # -- Language ---------------------------------------------------------------- env_tags = os.getenv("SPHINX_TAGS") -if env_tags != None: +if env_tags is not None: for tag in env_tags.split(","): print("Adding Sphinx tag: %s" % tag.strip()) tags.add(tag.strip()) diff --git a/examples/random_trackgen.py b/examples/random_trackgen.py index b9d17dbe..fb725652 100644 --- a/examples/random_trackgen.py +++ b/examples/random_trackgen.py @@ -54,7 +54,7 @@ def main(args): track, track_int, track_ext = create_track() convert_track(track, track_int, track_ext, i, outdir) print(f"[info] saved track {i} in {outdir}/") - except: + except Exception as _: # noqa: F841 print("[error] failed to create track. Retrying...") continue print() diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index 12bfa0ad..ee4763c1 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -230,7 +230,7 @@ def _get_current_waypoint(self, waypoints, lookahead_distance, position, theta): lookahead_point, i2, t2 = first_point_on_trajectory_intersecting_circle( position, lookahead_distance, wpts, t1, wrap=True ) - if i2 == None: + if i2 is None: return None current_waypoint = np.empty((3,), dtype=np.float32) # x, y diff --git a/gym/f110_gym/envs/__init__.py b/gym/f110_gym/envs/__init__.py index 86fed2dc..33077f3c 100644 --- a/gym/f110_gym/envs/__init__.py +++ b/gym/f110_gym/envs/__init__.py @@ -1 +1 @@ -from .f110_env import F110Env +from .f110_env import F110Env # noqa: F401 This is needed to make easy imports work diff --git a/gym/f110_gym/envs/base_classes.py b/gym/f110_gym/envs/base_classes.py index a03cbf98..055817f8 100644 --- a/gym/f110_gym/envs/base_classes.py +++ b/gym/f110_gym/envs/base_classes.py @@ -495,8 +495,6 @@ def step(self, control_inputs): observations (dict): dictionary for observations: poses of agents, current laser scan of each agent, collision indicators, etc. """ - agent_scans = [] - # looping over agents for i, agent in enumerate(self.agents): # update each agent's pose diff --git a/gym/f110_gym/envs/dynamic_models.py b/gym/f110_gym/envs/dynamic_models.py index 0c996f5f..d1f5e7a5 100644 --- a/gym/f110_gym/envs/dynamic_models.py +++ b/gym/f110_gym/envs/dynamic_models.py @@ -41,7 +41,7 @@ class DynamicModel(Enum): def from_string(model: str): if model == "ks": warnings.warn( - f"Chosen model is KS. This is different from previous versions of the gym." + "Chosen model is KS. This is different from previous versions of the gym." ) return DynamicModel.KS elif model == "st": @@ -547,7 +547,3 @@ def func_ST( v_max, ) return f - - -if __name__ == "__main__": - unittest.main() diff --git a/gym/f110_gym/envs/f110_env_backup.py b/gym/f110_gym/envs/f110_env_backup.py index 56a7411c..4e60cdfc 100644 --- a/gym/f110_gym/envs/f110_env_backup.py +++ b/gym/f110_gym/envs/f110_env_backup.py @@ -150,7 +150,7 @@ def __init__(self): # self.socket.connect('tcp://localhost:6666') self.port = min_port + tries break - except: + except Exception as _: # noqa: F841 tries = tries + 1 # print('Gym env - retrying for ' + str(tries) + ' times') diff --git a/gym/f110_gym/envs/integrator.py b/gym/f110_gym/envs/integrator.py index ec048807..57eb9cb5 100644 --- a/gym/f110_gym/envs/integrator.py +++ b/gym/f110_gym/envs/integrator.py @@ -11,7 +11,7 @@ class IntegratorType(Enum): def from_string(integrator: str): if integrator == "rk4": warnings.warn( - f"Chosen integrator is RK4. This is different from previous versions of the gym." + "Chosen integrator is RK4. This is different from previous versions of the gym." ) return RK4Integrator() elif integrator == "euler": diff --git a/gym/f110_gym/envs/laser_models.py b/gym/f110_gym/envs/laser_models.py index 6e4c5438..e8888bd4 100644 --- a/gym/f110_gym/envs/laser_models.py +++ b/gym/f110_gym/envs/laser_models.py @@ -623,7 +623,7 @@ def test_fps(self): start = time.time() for i in range(10000): x_test = i / 10000 - scan = scan_sim.scan(np.array([x_test, 0.0, 0.0]), scan_rng) + scan_sim.scan(np.array([x_test, 0.0, 0.0]), scan_rng) end = time.time() fps = 10000 / (end - start) # print('FPS test') @@ -668,7 +668,7 @@ def main(): scan_rng = np.random.default_rng(seed=12345) scan_sim = ScanSimulator2D(num_beams, fov) scan_sim.set_map(map_path, map_ext) - scan = scan_sim.scan(np.array([0.0, 0.0, 0.0]), scan_rng) + scan_sim.scan(np.array([0.0, 0.0, 0.0]), scan_rng) # fps test import time @@ -676,7 +676,7 @@ def main(): start = time.time() for i in range(10000): x_test = i / 10000 - scan = scan_sim.scan(np.array([x_test, 0.0, 0.0]), scan_rng) + scan_sim.scan(np.array([x_test, 0.0, 0.0]), scan_rng) end = time.time() fps = (end - start) / 10000 print("FPS test") @@ -702,7 +702,7 @@ def update(i): line.set_data(theta, current_scan) return (line,) - ani = FuncAnimation(fig, update, frames=num_iter, blit=True) + FuncAnimation(fig, update, frames=num_iter, blit=True) plt.show() diff --git a/gym/f110_gym/envs/observation.py b/gym/f110_gym/envs/observation.py index 7993b751..2849fd4f 100644 --- a/gym/f110_gym/envs/observation.py +++ b/gym/f110_gym/envs/observation.py @@ -17,7 +17,7 @@ class Observation: :param kwargs: Additional arguments. """ - def __init__(self, env: "F110Env"): + def __init__(self, env): self.env = env @abstractmethod @@ -30,7 +30,7 @@ def observe(self): class OriginalObservation(Observation): - def __init__(self, env: "F110Env"): + def __init__(self, env): super().__init__(env) def space(self): @@ -152,7 +152,7 @@ def observe(self): class FeaturesObservation(Observation): - def __init__(self, env: "F110Env", features: List[str]): + def __init__(self, env, features: List[str]): super().__init__(env) self.features = features @@ -263,7 +263,7 @@ def observe(self): return obs -def observation_factory(env: "F110Env", type: str, **kwargs) -> Observation: +def observation_factory(env, type: str, **kwargs) -> Observation: if type == "original": return OriginalObservation(env) elif type == "features": diff --git a/gym/f110_gym/envs/rendering.py b/gym/f110_gym/envs/rendering.py index 98f5c4f7..9d863f43 100644 --- a/gym/f110_gym/envs/rendering.py +++ b/gym/f110_gym/envs/rendering.py @@ -20,6 +20,7 @@ # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE # SOFTWARE. +# flake8: noqa """ Rendering engine for f1tenth gym env based on pyglet and OpenGL diff --git a/setup.cfg b/setup.cfg index 6721ba54..a59f8a19 100644 --- a/setup.cfg +++ b/setup.cfg @@ -6,7 +6,7 @@ testpaths = integration [flake8] -extend-ignore = E203, E501 +extend-ignore = E203, E501, max-line-length = 120 exclude = .git, diff --git a/tests/pyglet_test_.py b/tests/pyglet_test_.py index c1cac494..a05331e4 100644 --- a/tests/pyglet_test_.py +++ b/tests/pyglet_test_.py @@ -1,3 +1,4 @@ +# flake8: noqa import argparse import numpy as np diff --git a/tests/pyglet_test_camera.py b/tests/pyglet_test_camera.py index 6f5f973c..026e1ab1 100644 --- a/tests/pyglet_test_camera.py +++ b/tests/pyglet_test_camera.py @@ -1,3 +1,4 @@ +# flake8: noqa import pyglet from pyglet.gl import * diff --git a/tests/test_collision_checks.py b/tests/test_collision_checks.py index 08315a6c..41c36bdf 100644 --- a/tests/test_collision_checks.py +++ b/tests/test_collision_checks.py @@ -282,7 +282,7 @@ def test_get_vert_fps(self): test_pose = np.array([2.3, 6.7, 0.8]) start = time.time() for _ in range(1000): - vertices = get_vertices(test_pose, self.length, self.width) + get_vertices(test_pose, self.length, self.width) elapsed = time.time() - start fps = 1000 / elapsed print("get vertices fps:", fps) diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 21fae8c9..9feede93 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -12,7 +12,7 @@ """ -Prototype of vehicle dynamics functions and classes for simulating 2D Single +Prototype of vehicle dynamics functions and classes for simulating 2D Single Track dynamic model Following the implementation of commanroad's Single Track Dynamics model Original implementation: https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ @@ -124,7 +124,7 @@ def setUp(self): self.lr = 0.3048 * 4.667707 self.h = 0.3048 * 2.01355 self.m = 4.4482216152605 / 0.3048 * 74.91452 - self.I = 4.4482216152605 * 0.3048 * 1321.416 + self.I = 4.4482216152605 * 0.3048 * 1321.416 # noqa: E741 # steering constraints self.s_min = -1.066 # minimum steering angle [rad] @@ -257,7 +257,7 @@ def test_zeroinit_roll(self): from scipy.integrate import odeint # testing for zero initial state, zero input singularities - g = 9.81 + # g = 9.81 t_start = 0.0 t_final = 1.0 delta0 = 0.0 @@ -530,7 +530,7 @@ def test_zeroinit_rollleft(self): from scipy.integrate import odeint # testing for zero initial state, rolling and steering left input singularities - g = 9.81 + # g = 9.81 t_start = 0.0 t_final = 1.0 delta0 = 0.0 @@ -634,7 +634,7 @@ def setUp(self): self.lr = 0.3048 * 4.667707 self.h = 0.3048 * 2.01355 self.m = 4.4482216152605 / 0.3048 * 74.91452 - self.I = 4.4482216152605 * 0.3048 * 1321.416 + self.I = 4.4482216152605 * 0.3048 * 1321.416 # noqa: E741 # steering constraints self.s_min = -1.066 # minimum steering angle [rad] @@ -767,7 +767,7 @@ def test_zeroinit_roll(self): from scipy.integrate import odeint # testing for zero initial state, zero input singularities - g = 9.81 + # g = 9.81 t_start = 0.0 t_final = 1.0 delta0 = 0.0 @@ -1040,7 +1040,7 @@ def test_zeroinit_rollleft(self): from scipy.integrate import odeint # testing for zero initial state, rolling and steering left input singularities - g = 9.81 + # g = 9.81 t_start = 0.0 t_final = 1.0 delta0 = 0.0 diff --git a/tests/test_observation.py b/tests/test_observation.py index 3d047bca..f55a07f5 100644 --- a/tests/test_observation.py +++ b/tests/test_observation.py @@ -123,7 +123,7 @@ def test_unexisting_obs_space(self): """ env = self._make_env() with self.assertRaises(ValueError): - obs = observation_factory(env, vehicle_id=0, type="unexisting_obs_type") + observation_factory(env, vehicle_id=0, type="unexisting_obs_type") def test_kinematic_obs_space(self): """ diff --git a/tests/test_scan_sim.py b/tests/test_scan_sim.py index a97599c0..bb79b26d 100644 --- a/tests/test_scan_sim.py +++ b/tests/test_scan_sim.py @@ -332,7 +332,7 @@ def test_fps(self): start = time.time() for i in range(10000): x_test = i / 10000 - scan = scan_sim.scan(pose=np.array([x_test, 0.0, 0.0]), rng=scan_rng) + scan_sim.scan(pose=np.array([x_test, 0.0, 0.0]), rng=scan_rng) end = time.time() fps = 10000 / (end - start) @@ -346,7 +346,7 @@ def main(): scan_rng = np.random.default_rng(seed=12345) scan_sim = ScanSimulator2D(num_beams, fov) scan_sim.set_map(map_name="Example") - scan = scan_sim.scan(np.array([0.0, 0.0, 0.0])) + scan_sim.scan(np.array([0.0, 0.0, 0.0])) # fps test import time @@ -354,7 +354,7 @@ def main(): start = time.time() for i in range(10000): x_test = i / 10000 - scan = scan_sim.scan(np.array([x_test, 0.0, 0.0]), rng=scan_rng) + scan_sim.scan(np.array([x_test, 0.0, 0.0]), rng=scan_rng) end = time.time() fps = (end - start) / 10000 print("FPS test") @@ -380,7 +380,7 @@ def update(i): line.set_data(theta, current_scan) return (line,) - ani = FuncAnimation(fig, update, frames=num_iter, blit=True) + FuncAnimation(fig, update, frames=num_iter, blit=True) plt.show() diff --git a/tests/test_track.py b/tests/test_track.py index 8c0d16be..447d08da 100644 --- a/tests/test_track.py +++ b/tests/test_track.py @@ -89,12 +89,12 @@ def test_map_dir_structure(self): if file_raceline.exists(): # try to load raceline files # it will raise an assertion error if the file format are not valid - raceline = Raceline.from_raceline_file(file_raceline) + Raceline.from_raceline_file(file_raceline) if file_centerline.exists(): # try to load raceline files # it will raise an assertion error if the file format are not valid - centerline = Raceline.from_centerline_file(file_centerline) + Raceline.from_centerline_file(file_centerline) def test_download_racetrack(self): import shutil From 8e2b63940b5ce9eebf0f35bc3a666bb5bcdc8e4b Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:23:28 -0400 Subject: [PATCH 22/32] Only single track model error remains. --- tests/test_collision_checks.py | 4 +- tests/test_dynamics.py | 585 +-------------------------------- 2 files changed, 7 insertions(+), 582 deletions(-) diff --git a/tests/test_collision_checks.py b/tests/test_collision_checks.py index 41c36bdf..00aeb4cf 100644 --- a/tests/test_collision_checks.py +++ b/tests/test_collision_checks.py @@ -286,7 +286,7 @@ def test_get_vert_fps(self): elapsed = time.time() - start fps = 1000 / elapsed print("get vertices fps:", fps) - self.assertTrue(fps > 500) + self.assertGreater(fps, 500) def test_random_collision(self): # perturb the body by a small amount and make sure it all collides with the original body @@ -305,7 +305,7 @@ def test_fps(self): elapsed = time.time() - start fps = 1000 / elapsed print("gjk fps:", fps) - self.assertTrue(fps > 500) + # self.assertGreater(fps, 500) This is a platform dependent test, not ideal. if __name__ == "__main__": diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 9feede93..03ddfc1e 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -23,95 +23,7 @@ import unittest import numpy as np -from f110_gym.envs.dynamic_models import vehicle_dynamics_ks, vehicle_dynamics_st - - -def func_KS( - x, - t, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): - f = vehicle_dynamics_ks( - x, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, - ) - return f - - -def func_ST( - x, - t, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): - f = vehicle_dynamics_st( - x, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, - ) - return f +from f110_gym.envs.dynamic_models import vehicle_dynamics_ks, vehicle_dynamics_st, func_KS, func_ST class DynamicsTest(unittest.TestCase): @@ -526,7 +438,7 @@ def test_zeroinit_acc(self): self.assertTrue(all(abs(x_acc_st[-1] - x_acc_st_gt) < 1e-2)) self.assertTrue(all(abs(x_acc_ks[-1] - x_acc_ks_gt) < 1e-2)) - def test_zeroinit_rollleft(self): + def test_zeroinit_rollleft_kinematic(self): from scipy.integrate import odeint # testing for zero initial state, rolling and steering left input singularities @@ -542,7 +454,6 @@ def test_zeroinit_rollleft(self): initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) # time vector t = np.arange(t_start, t_final, 1e-4) @@ -550,31 +461,6 @@ def test_zeroinit_rollleft(self): # set decel input u = np.array([0.15, 0.0]) - # simulate single-track model - x_left_st = odeint( - func_ST, - x0_ST, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) # simulate kinematic single-track model x_left_ks = odeint( func_KS, @@ -600,17 +486,6 @@ def test_zeroinit_rollleft(self): self.v_max, ), ) - - # ground truth for single-track model - x_left_st_gt = [ - 0.0000000000000000, - 0.0000000000000000, - 0.1500000000000000, - 0.0000000000000000, - 0.0000000000000000, - 0.0000000000000000, - 0.0000000000000000, - ] # ground truth for kinematic single-track model x_left_ks_gt = [ 0.0000000000000000, @@ -619,424 +494,9 @@ def test_zeroinit_rollleft(self): 0.0000000000000000, 0.0000000000000000, ] + np.testing.assert_array_almost_equal(x_left_ks[-1], x_left_ks_gt, decimal=2) - self.assertTrue(all(abs(x_left_st[-1] - x_left_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_left_ks[-1] - x_left_ks_gt) < 1e-2)) - - -class DynamicsTest2(unittest.TestCase): - def setUp(self): - # test params - self.mu = 1.0489 - self.C_Sf = 21.92 / 1.0489 - self.C_Sr = 21.92 / 1.0489 - self.lf = 0.3048 * 3.793293 - self.lr = 0.3048 * 4.667707 - self.h = 0.3048 * 2.01355 - self.m = 4.4482216152605 / 0.3048 * 74.91452 - self.I = 4.4482216152605 * 0.3048 * 1321.416 # noqa: E741 - - # steering constraints - self.s_min = -1.066 # minimum steering angle [rad] - self.s_max = 1.066 # maximum steering angle [rad] - self.sv_min = -0.4 # minimum steering velocity [rad/s] - self.sv_max = 0.4 # maximum steering velocity [rad/s] - - # longitudinal constraints - self.v_min = -13.6 # minimum velocity [m/s] - self.v_max = 50.8 # minimum velocity [m/s] - self.v_switch = 7.319 # switching velocity [m/s] - self.a_max = 11.5 # maximum absolute acceleration [m/s^2] - - def test_derivatives(self): - # ground truth derivatives - f_ks_gt = [ - 16.3475935934250209, - 0.4819314886013121, - 0.1500000000000000, - 5.1464424102339752, - 0.2401426578627629, - ] - f_st_gt = [ - 15.7213512030862397, - 0.0925527979719355, - 0.1500000000000000, - 5.3536773276413925, - 0.0529001056654038, - 0.6435589397748606, - 0.0313297971641291, - ] - - # system dynamics - g = 9.81 - x_ks = np.array( - [ - 3.9579422297936526, - 0.0391650102771405, - 0.0378491427211811, - 16.3546957860883566, - 0.0294717351052816, - ] - ) - x_st = np.array( - [ - 2.0233348142065677, - 0.0041907137716636, - 0.0197545248559617, - 15.7216236334290116, - 0.0025857914776859, - 0.0529001056654038, - 0.0033012170610298, - ] - ) - v_delta = 0.15 - acc = 0.63 * g - u = np.array([v_delta, acc]) - - f_ks = vehicle_dynamics_ks( - x_ks, - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ) - f_st = vehicle_dynamics_st( - x_st, - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ) - - start = time.time() - for i in range(10000): - f_st = vehicle_dynamics_st( - x_st, - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ) - duration = time.time() - start - avg_fps = 10000 / duration - - self.assertAlmostEqual(np.max(np.abs(f_ks_gt - f_ks)), 0.0) - self.assertAlmostEqual(np.max(np.abs(f_st_gt - f_st)), 0.0) - self.assertGreater(avg_fps, 5000) - - def test_zeroinit_roll(self): - from scipy.integrate import odeint - - # testing for zero initial state, zero input singularities - # g = 9.81 - t_start = 0.0 - t_final = 1.0 - delta0 = 0.0 - vel0 = 0.0 - Psi0 = 0.0 - dotPsi0 = 0.0 - beta0 = 0.0 - sy0 = 0.0 - initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set input: rolling car (velocity should stay constant) - u = np.array([0.0, 0.0]) - - # simulate single-track model - x_roll_st = odeint( - func_ST, - x0_ST, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) - # simulate kinematic single-track model - x_roll_ks = odeint( - func_KS, - x0_KS, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) - - self.assertTrue(all(x_roll_st[-1] == x0_ST)) - self.assertTrue(all(x_roll_ks[-1] == x0_KS)) - - def test_zeroinit_dec(self): - from scipy.integrate import odeint - - # testing for zero initial state, decelerating input singularities - g = 9.81 - t_start = 0.0 - t_final = 1.0 - delta0 = 0.0 - vel0 = 0.0 - Psi0 = 0.0 - dotPsi0 = 0.0 - beta0 = 0.0 - sy0 = 0.0 - initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set decel input - u = np.array([0.0, -0.7 * g]) - - # simulate single-track model - x_dec_st = odeint( - func_ST, - x0_ST, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) - # simulate kinematic single-track model - x_dec_ks = odeint( - func_KS, - x0_KS, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) - - # ground truth for single-track model - x_dec_st_gt = [ - -3.4335000000000013, - 0.0000000000000000, - 0.0000000000000000, - -6.8670000000000018, - 0.0000000000000000, - 0.0000000000000000, - 0.0000000000000000, - ] - # ground truth for kinematic single-track model - x_dec_ks_gt = [ - -3.4335000000000013, - 0.0000000000000000, - 0.0000000000000000, - -6.8670000000000018, - 0.0000000000000000, - ] - - self.assertTrue(all(abs(x_dec_st[-1] - x_dec_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_dec_ks[-1] - x_dec_ks_gt) < 1e-2)) - - def test_zeroinit_acc(self): - from scipy.integrate import odeint - - # testing for zero initial state, accelerating with left steer input singularities - # wheel spin and velocity should increase more wheel spin at rear - g = 9.81 - t_start = 0.0 - t_final = 1.0 - delta0 = 0.0 - vel0 = 0.0 - Psi0 = 0.0 - dotPsi0 = 0.0 - beta0 = 0.0 - sy0 = 0.0 - initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] - - x0_KS = np.array(initial_state[0:5]) - x0_ST = np.array(initial_state) - - # time vector - t = np.arange(t_start, t_final, 1e-4) - - # set decel input - u = np.array([0.15, 0.63 * g]) - - # simulate single-track model - x_acc_st = odeint( - func_ST, - x0_ST, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) - # simulate kinematic single-track model - x_acc_ks = odeint( - func_KS, - x0_KS, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) - - # ground truth for single-track model - x_acc_st_gt = [ - 3.0731976046859715, - 0.2869835398304389, - 0.1500000000000000, - 6.1802999999999999, - 0.1097747074946325, - 0.3248268063223301, - 0.0697547542798040, - ] - # ground truth for kinematic single-track model - x_acc_ks_gt = [ - 3.0845676868494927, - 0.1484249221523042, - 0.1500000000000000, - 6.1803000000000017, - 0.1203664469224163, - ] - - self.assertTrue(all(abs(x_acc_st[-1] - x_acc_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_acc_ks[-1] - x_acc_ks_gt) < 1e-2)) - - def test_zeroinit_rollleft(self): + def test_zeroinit_rollleft_singletrack(self): from scipy.integrate import odeint # testing for zero initial state, rolling and steering left input singularities @@ -1051,7 +511,6 @@ def test_zeroinit_rollleft(self): sy0 = 0.0 initial_state = [0, sy0, delta0, vel0, Psi0, dotPsi0, beta0] - x0_KS = np.array(initial_state[0:5]) x0_ST = np.array(initial_state) # time vector @@ -1085,31 +544,6 @@ def test_zeroinit_rollleft(self): self.v_max, ), ) - # simulate kinematic single-track model - x_left_ks = odeint( - func_KS, - x0_KS, - t, - args=( - u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, - ), - ) # ground truth for single-track model x_left_st_gt = [ @@ -1121,17 +555,8 @@ def test_zeroinit_rollleft(self): 0.0000000000000000, 0.0000000000000000, ] - # ground truth for kinematic single-track model - x_left_ks_gt = [ - 0.0000000000000000, - 0.0000000000000000, - 0.1500000000000000, - 0.0000000000000000, - 0.0000000000000000, - ] - self.assertTrue(all(abs(x_left_st[-1] - x_left_st_gt) < 1e-2)) - self.assertTrue(all(abs(x_left_ks[-1] - x_left_ks_gt) < 1e-2)) + np.testing.assert_array_almost_equal(x_left_st[-1], x_left_st_gt, decimal=2) if __name__ == "__main__": From 69705d42b02985907491f3f773e6af17e7c087a2 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:25:21 -0400 Subject: [PATCH 23/32] Tightened up testing matrices --- .github/workflows/ci.yml | 2 +- .github/workflows/lint.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 2e0fab90..2163a788 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -16,7 +16,7 @@ jobs: strategy: fail-fast: false matrix: - python-version: ["3.8", "3.9", "3.10", "3.11"] + python-version: ["3.9", "3.10", "3.11"] steps: - uses: actions/checkout@v2 diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index fff77426..8bb086f6 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -16,7 +16,7 @@ jobs: strategy: fail-fast: false matrix: - python-version: ["3.8", "3.9", "3.10", "3.11"] + python-version: ["3.9"] steps: - uses: actions/checkout@v2 From 242b59bf384f41c6fa073fd8bace9eb2fc75c58a Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:28:59 -0400 Subject: [PATCH 24/32] Linting update --- .github/workflows/lint.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index 8bb086f6..aa07f0d8 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -41,4 +41,4 @@ jobs: run: | # stop the build if there are Python syntax errors or undefined names # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide - flake8 . --count --max-complexity=10 --max-line-length=127 --statistics + flake8 . --statistics --exit-zero From 46409e301215bed7040e5cbe4421680f40c0cca0 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:33:02 -0400 Subject: [PATCH 25/32] Update to install OpenGL on GH Actions --- .github/workflows/ci.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 2163a788..9668f4aa 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -19,6 +19,9 @@ jobs: python-version: ["3.9", "3.10", "3.11"] steps: + - name: Install openGL + run: sudo apt install freeglut3-dev + - uses: actions/checkout@v2 - name: Set up Python ${{ matrix.python-version }} From 927a59b7fe741876d1873b3049a828c412ad0eff Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:37:07 -0400 Subject: [PATCH 26/32] Fix CI render test --- tests/test_f110_env.py | 2 +- tests/test_observation.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/test_f110_env.py b/tests/test_f110_env.py index f2a56957..c4ba7fa7 100644 --- a/tests/test_f110_env.py +++ b/tests/test_f110_env.py @@ -28,7 +28,7 @@ def test_gymnasium_api(self): from gymnasium.utils.env_checker import check_env env = self._make_env() - check_env(env.unwrapped) + check_env(env.unwrapped, skip_render_check=True) def test_configure_method(self): """ diff --git a/tests/test_observation.py b/tests/test_observation.py index f55a07f5..d88b345b 100644 --- a/tests/test_observation.py +++ b/tests/test_observation.py @@ -228,5 +228,5 @@ def test_gymnasium_api(self): for obs_type_id in obs_type_ids: env = self._make_env(config={"observation_config": {"type": obs_type_id}}) check_env( - env.unwrapped, f"Observation {obs_type_id} breaks the gymnasium API" + env.unwrapped, f"Observation {obs_type_id} breaks the gymnasium API", skip_render_check=True ) From 8cfc9e63907ded5ab079f14c4c18a07e020a0ed0 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:46:15 -0400 Subject: [PATCH 27/32] Fixing test bug. --- gym/f110_gym/envs/track.py | 1 + .../Spielberg_DonkeySim_waypoints.txt | 864 +++++++++ .../maps/Spielberg/Spielberg_centerline.csv | 865 +++++++++ gym/f110_gym/maps/Spielberg/Spielberg_map.png | Bin 0 -> 62176 bytes .../maps/Spielberg/Spielberg_map.yaml | 6 + .../maps/Spielberg/Spielberg_raceline.csv | 1695 +++++++++++++++++ 6 files changed, 3431 insertions(+) create mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt create mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv create mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_map.png create mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_map.yaml create mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv diff --git a/gym/f110_gym/envs/track.py b/gym/f110_gym/envs/track.py index 710cd68d..39c05e48 100644 --- a/gym/f110_gym/envs/track.py +++ b/gym/f110_gym/envs/track.py @@ -239,6 +239,7 @@ def from_track_name(track: str): raceline=raceline, ) except Exception as ex: + print(ex) raise FileNotFoundError(f"could not load track {track}") from ex diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt b/gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt new file mode 100644 index 00000000..394a486d --- /dev/null +++ b/gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt @@ -0,0 +1,864 @@ +76.08812195356482,0.0,9.120088008544716 +75.70418495495521,0.0,9.016879535734098 +75.32024660388215,0.0,8.913676313663823 +74.93630793458243,0.0,8.810476751200465 +74.55236974262274,0.0,8.707278938983892 +74.1684328235698,0.0,8.60408128588066 +73.78449821166033,0.0,8.500882041643997 +73.40056662290442,0.0,8.39767937647043 +73.01663893242544,0.0,8.294471699226522 +72.63271593579009,0.0,8.191257498335517 +72.24879747388505,0.0,8.088036773797409 +71.86488330804029,0.0,7.984809764282204 +71.48097335869917,0.0,7.881576628903261 +71.09706738719163,0.0,7.778337526773916 +70.71316515484767,0.0,7.675092696564183 +70.32926642299729,0.0,7.5718424565007565 +69.94537103252715,0.0,7.468586806583637 +69.56147882432387,0.0,7.365326144596175 +69.17758955971746,0.0,7.262060550095057 +68.79370300003788,0.0,7.158790261750282 +68.40981898617183,0.0,7.05551543867521 +68.02593727944925,0.0,6.952236319539839 +67.64205772075682,0.0,6.84895322257088 +67.2581801509812,0.0,6.7456661477683095 +66.87430417233901,0.0,6.6423754133588355 +66.49042978483027,0.0,6.53908125801246 +66.10655674978494,0.0,6.43578376128586 +65.72268474897636,0.0,6.332483241405731 +65.33881370284784,0.0,6.2291798574854 +64.95494337272936,0.0,6.125873768638227 +64.57107351995091,0.0,6.02256529309089 +64.18720398539917,0.0,5.919254510400069 +63.803334530404086,0.0,5.815941738792448 +63.41946491629565,0.0,5.712627057824695 +63.03559506351721,0.0,5.609310785723501 +62.65172473339874,0.0,5.505993081602217 +62.26785360771354,0.0,5.402674104574179 +61.88398160690495,0.0,5.2993541728660745 +61.50010849230296,0.0,5.196033366034575 +61.116234025237546,0.0,5.092711922749703 +60.732358126152036,0.0,4.989390081681472 +60.34848039726305,0.0,4.886068001943226 +59.96460075901395,0.0,4.782745922204973 +59.580718972734715,0.0,4.679424081136742 +59.19683487931197,0.0,4.576102637851869 +58.81294824007574,0.0,4.472781751463705 +58.42905889591266,0.0,4.369461660642257 +58.04516652859604,0.0,4.266142604057548 +57.66127105856921,0.0,4.162824740822914 +57.27737224716215,0.0,4.059508389165048 +56.89346985570485,0.0,3.9561935490839506 +56.509563725083986,0.0,3.852880538806316 +56.125653616629506,0.0,3.749569597002144 +55.741739371228086,0.0,3.646260882784798 +55.357820750209704,0.0,3.542954634824275 +54.973897594461015,0.0,3.4396509326772655 +54.58996966531201,0.0,3.336350174127114 +54.20603672409267,0.0,3.2330523591738283 +53.822098611689654,0.0,3.1297578856007657 +53.438155089432925,0.0,3.026466832964598 +53.054205998209156,0.0,2.923179439935348 +52.67025117890502,0.0,2.819895865626351 +52.28629031329379,0.0,2.7166164282642944 +51.90232443561224,0.0,2.6133414460758786 +51.51835879660071,0.0,2.5100723510811864 +51.134399840349616,0.0,2.406810654856989 +50.75045393139273,0.0,2.303558028093403 +50.366527434263816,0.0,2.2003159028105213 +49.98262679305331,0.0,2.0970859496984575 +49.598758213181625,0.0,1.993869759890651 +49.21492821829585,0.0,1.890668765407196 +48.83114317292977,0.0,1.7874846369382071 +48.44740936206046,0.0,1.6843189656171216 +48.06373330933502,0.0,1.581173342577384 +47.68012122017389,0.0,1.4780491998390888 +47.29657953866746,0.0,1.3749482080923494 +46.91311256087606,0.0,1.2718706855638473 +46.52964542397132,0.0,1.168769534703765 +46.14600238726476,0.0,1.0655372744482108 +45.76200118642084,0.0,0.9620626845697249 +45.3774594775473,0.0,0.8582343061708269 +44.992195075865254,0.0,0.7539408394673828 +44.60602571703913,0.0,0.6490709051185775 +44.21907137253034,0.0,0.5437511573462448 +43.8359202347268,0.0,0.4416250530582708 +43.463249892893394,0.0,0.3477037874676654 +43.088186009025996,0.0,0.24749611276845407 +42.6912361642463,0.0,0.12588713640279714 +42.286127623639,0.0,0.024688822023767543 +41.894964890294396,0.0,0.0 +41.53795671136556,0.0,0.09980448148548327 +41.22166388692285,0.0,0.31365679367245214 +40.94666845357865,0.0,0.6055162525652165 +40.71349914497514,0.0,0.9392832226741117 +40.51764740495302,0.0,1.2878009544530808 +40.343783856166745,0.0,1.6431236457287843 +40.17517741226665,0.0,1.9997938679149394 +39.9981389953706,0.0,2.353288903764641 +39.81072750223833,0.0,2.7026963178066525 +39.61383794542989,0.0,3.0479752179115644 +39.40836509883534,0.0,3.389084711949959 +39.195204054571434,0.0,3.725983828235753 +38.97524958652823,0.0,4.058631754196212 +38.74939718460582,0.0,4.386988950165342 +38.51862181581965,0.0,4.71130100758964 +38.28407291496687,0.0,5.032435730647333 +38.046922510939474,0.0,5.3513427873321815 +37.808343030412836,0.0,5.6689720047512635 +37.56950658183561,0.0,5.9862731304549825 +37.331585432769835,0.0,6.304195911993769 +37.095733393629594,0.0,6.623675538047042 +36.86240688104219,0.0,6.945092528177021 +36.631164991931364,0.0,7.268114176381371 +36.40150779217025,0.0,7.592360917777945 +36.17293542718862,0.0,7.917452948814591 +35.94494804241624,0.0,8.243010625052488 +35.71704570372624,0.0,8.5686543816095 +35.488815909774274,0.0,8.89407060608457 +35.26019549256273,0.0,9.219210768907777 +35.031208637319956,0.0,9.544092452103635 +34.80187952927419,0.0,9.86873315813999 +34.57223235365374,0.0,10.193150469041345 +34.34229129568691,0.0,10.517361966832222 +34.11208046104529,0.0,10.841385233537137 +33.881624114513876,0.0,11.165237771623916 +33.650946441320926,0.0,11.488937242673758 +33.42007154713808,0.0,11.812501149154505 +33.18902369675028,0.0,12.135947073090668 +32.95782699582917,0.0,12.459292596506753 +32.726505709159696,0.0,12.782555221870611 +32.49508394241347,0.0,13.105752610763417 +32.26358596037547,0.0,13.428902345209696 +32.03203594827398,0.0,13.752021848120616 +31.800457932223942,0.0,14.07512878107735 +31.568876256566988,0.0,14.398240726104426 +31.33731502697475,0.0,14.721375265226351 +31.105798428675477,0.0,15.044549900910972 +30.874350726454196,0.0,15.367782215182796 +30.642995946425806,0.0,15.691089790066334 +30.411758432931947,0.0,16.0144902075861 +30.180662291644254,0.0,16.33800097020995 +29.949731707790995,0.0,16.661639739519053 +29.718990866600485,0.0,16.985424017981252 +29.488463873744315,0.0,17.30937146717774 +29.258236173088235,0.0,17.63353737899556 +29.028869116509924,0.0,17.95827228013156 +28.80114745102206,0.0,18.2840648872219 +28.57585711698738,0.0,18.61140487158276 +28.35378429343865,0.0,18.94078182497367 +28.135714920738636,0.0,19.272685339154165 +27.92243509836343,0.0,19.607605005883762 +27.714487800599457,0.0,19.945876952101706 +27.51138462903731,0.0,20.287186372056855 +27.312363669429132,0.0,20.63104558334981 +27.11666300752716,0.0,20.97696706269451 +26.92352056997023,0.0,21.324463127691565 +26.732174522067197,0.0,21.67304617549825 +26.541863506466967,0.0,22.022229080611858 +26.35204765159331,0.0,22.371664021262383 +26.162714626162064,0.0,22.72133564301212 +25.9739292688609,0.0,23.07127712099332 +25.785756418377517,0.0,23.42152155078151 +25.598260913399614,0.0,23.7721021870656 +25.41150751305817,0.0,24.12305220497782 +25.225561056040902,0.0,24.474404700093714 +25.040486381035457,0.0,24.82619292710219 +24.85634832672956,0.0,25.178449902022134 +24.673211652254196,0.0,25.5312089590991 +24.491141275853757,0.0,25.88450327346533 +24.31020187710255,0.0,26.23836586113971 +24.130458374244938,0.0,26.592829976811124 +23.951956989707362,0.0,26.947919248811157 +23.77466232077078,0.0,27.303615538218608 +23.59851637062132,0.0,27.659889170394816 +23.423461301558383,0.0,28.016710311587765 +23.2494391963248,0.0,28.374049446272146 +23.07639213766332,0.0,28.731876820252634 +22.90426220831673,0.0,29.090162679333893 +22.73299157058449,0.0,29.44887742843394 +22.562522227652686,0.0,29.807991313357448 +22.39279634182079,0.0,30.16747465946575 +22.223755995831574,0.0,30.527297792120194 +22.055343272427812,0.0,30.887431036682113 +21.887500333908967,0.0,31.24784463895619 +21.72016910390446,0.0,31.608508924303752 +21.553291903827095,0.0,31.969394218086148 +21.386810657306313,0.0,32.33047084566472 +21.220667526641556,0.0,32.69170913240082 +21.05480451501893,0.0,33.0530793240991 +20.889163864294574,0.0,33.41455174612091 +20.723687657211237,0.0,33.776096723827585 +20.55831789695506,0.0,34.137684582580476 +20.392996666268793,0.0,34.49928564774091 +20.22766612745191,0.0,34.860870165113575 +20.06226844280384,0.0,35.2224084600598 +19.896745535954054,0.0,35.58387085794094 +19.731039648758653,0.0,35.94522768411833 +19.56509278440373,0.0,36.30644918439663 +19.3988646076566,0.0,36.6675144353711 +19.232465702291336,0.0,37.02847801291876 +19.066084219837244,0.0,37.38943299834584 +18.899908789163646,0.0,37.750472950298615 +18.734128198253224,0.0,38.11169126831004 +18.5689310759753,0.0,38.473181511026375 +18.404506210312533,0.0,38.835037077980566 +18.24085765865521,0.0,39.19726584528313 +18.077126368058998,0.0,39.55947512120106 +17.912201011372645,0.0,39.92115510658013 +17.744970261444884,0.0,40.28179600226614 +17.574322870681137,0.0,40.64088808866151 +17.39914751193013,0.0,40.997921646168706 +17.21833261937062,0.0,41.35238623918016 +17.03064681483327,0.0,41.70349131304613 +16.83454558508774,0.0,42.04971288015763 +16.62843381886031,0.0,42.389408811247804 +16.410913068970437,0.0,42.721098477093946 +16.184332007489125,0.0,43.04638040990669 +15.954398427849469,0.0,43.36961344018856 +15.726886951089035,0.0,43.69521352013264 +15.504597494722432,0.0,44.02527108085255 +15.285801928720339,0.0,44.35833683845438 +15.068392319501271,0.0,44.6926647626576 +14.850260813040428,0.0,45.02650858451166 +14.62929931664295,0.0,45.358122353292714 +14.403399896727386,0.0,45.685759720493536 +14.17081707990991,0.0,46.00797275468361 +13.931560015207786,0.0,46.32475715980266 +13.686168335527249,0.0,46.63654492857965 +13.435181832887864,0.0,46.943768212856966 +13.179140378865831,0.0,47.24685908492023 +12.918583606367434,0.0,47.54624961705515 +12.654051307412182,0.0,47.84237212021738 +12.386083274019676,0.0,48.13565858713592 +12.115219298209446,0.0,48.426541169653106 +11.84199909244441,0.0,48.71545194005462 +11.566962528300806,0.0,49.002823129739454 +11.290649238684807,0.0,49.28908681099331 +11.013599015616037,0.0,49.57467513565848 +10.736348389290484,0.0,49.8600175506505 +10.459226008320186,0.0,50.14537953658382 +10.182234657188715,0.0,50.430769049125644 +9.90534840042092,0.0,50.7161716089617 +9.62854146165516,0.0,51.001572577664305 +9.351787905416288,0.0,51.286957316805825 +9.075061955342619,0.0,51.572311347071945 +8.798337675959047,0.0,51.85762003003502 +8.521589290903862,0.0,52.14286880682408 +8.244790944258668,0.0,52.42804303901147 +7.967916700548358,0.0,52.71312824728285 +7.69094078341125,0.0,52.99810979321066 +7.413837257372222,0.0,53.282973038367174 +7.136580346069593,0.0,53.56770358299478 +6.859143795801543,0.0,53.85228559531575 +6.5814974545894245,0.0,54.136693139855 +6.3036094202077635,0.0,54.420894473500425 +6.025447392647678,0.0,54.70485769402653 +5.746979151457069,0.0,54.98855089920784 +5.4681727148537504,0.0,55.27194234593223 +5.188995862385596,0.0,55.55500013197424 +4.909416373600351,0.0,55.837692514221715 +4.629402187159329,0.0,56.119987431335844 +4.348921082610261,0.0,56.401853219761165 +4.067940919057733,0.0,56.683257977272206 +3.786429555606162,0.0,56.96416980164351 +3.504354851360162,0.0,57.244556949762924 +3.2216847449808625,0.0,57.52438759896164 +2.938486223186075,0.0,57.80370630097602 +2.655110369569414,0.0,58.08277662706038 +2.37195878621111,0.0,58.36190113123837 +2.089433154748164,0.0,58.64138228797698 +1.8079349977041659,0.0,58.92152265129984 +1.527865996716102,0.0,59.202624775230575 +1.2496477225889464,0.0,59.4850177857213 +0.9751367893772596,0.0,59.770954329939826 +0.7085706241021796,0.0,60.06587791405492 +0.4544182432569528,0.0,60.37553181377537 +0.22565955654947345,0.0,60.70530106111595 +0.06008923392317911,0.0,61.059525790761285 +0.0,0.0,61.44235663340335 +0.08163055533233887,0.0,61.84022090257106 +0.3100769025455321,0.0,62.14836951050047 +0.6679514536325257,0.0,62.271529125960214 +1.0773922528139224,0.0,62.30272305838393 +1.4795477293130261,0.0,62.33598427092974 +1.874016837946229,0.0,62.37727800242136 +2.265436618898079,0.0,62.42497532999943 +2.6573098728803615,0.0,62.47740269951164 +3.0500586480380747,0.0,62.53276539199423 +3.443586839911461,0.0,62.58924824241866 +3.8377985031540334,0.0,62.6450361653131 +4.232597453749364,0.0,62.69831407520577 +4.6278876667943365,0.0,62.7472668070681 +5.023573435612519,0.0,62.790093277402605 +5.419583397869133,0.0,62.82588065295461 +5.815884855771969,0.0,62.855117013906934 +6.21244813468239,0.0,62.878413673727266 +6.609243798631738,0.0,62.89638202543996 +7.006242332094715,0.0,62.909633621182735 +7.4034143786593205,0.0,62.918779615309944 +7.800730263686916,0.0,62.92443163951596 +8.198160551208872,0.0,62.92720108682519 +8.595675805256505,0.0,62.92769919114862 +8.993246510304544,0.0,62.926537504623965 +9.390843150827664,0.0,62.92432742027563 +9.788436211300521,0.0,62.92168033112797 +10.185996255754517,0.0,62.919207630205335 +10.583496712261166,0.0,62.91747385165229 +10.980939808407285,0.0,62.91659101126305 +11.378343842227466,0.0,62.91641733904805 +11.775727111756268,0.0,62.916808439647625 +12.173108233254915,0.0,62.91761999725877 +12.570505584314652,0.0,62.91870745740843 +12.967937622083369,0.0,62.91992642473693 +13.365410949764886,0.0,62.920955172062634 +13.76287091192549,0.0,62.92055667269254 +14.160243361746872,0.0,62.91719874468049 +14.557453993297415,0.0,62.90934936519366 +14.954428500645427,0.0,62.89547643184251 +15.351092657415954,0.0,62.87404784223757 +15.747372237233996,0.0,62.84353292600943 +16.14324432777802,0.0,62.80383923830519 +16.538833673909743,0.0,62.759010246979656 +16.934291353749273,0.0,62.713827705803695 +17.329766695170008,0.0,62.67290701554711 +17.725371793522783,0.0,62.63718742227965 +18.12118246631602,0.0,62.60401809769 +18.517268802977746,0.0,62.570597214903486 +18.91341122709325,0.0,62.53398770070295 +19.30890828748545,0.0,62.4910281320562 +19.703013344787543,0.0,62.43853727631969 +20.09528947375687,0.0,62.374906895368866 +20.486206456541645,0.0,62.303130786327955 +20.87639891671445,0.0,62.22703984162412 +21.26642359186601,0.0,62.14999517153626 +21.6564216950891,0.0,62.072844452404624 +22.046395692640587,0.0,61.995598185709895 +22.43634805077729,0.0,61.91826623647944 +22.826281156199364,0.0,61.840858549297195 +23.21619747516364,0.0,61.763385068747226 +23.606099473926953,0.0,61.68585565985684 +23.995989539189466,0.0,61.60828026721002 +24.385870137208016,0.0,61.5306688353908 +24.77574373423942,0.0,61.4530311498698 +25.16561279654053,0.0,61.37537731434439 +25.55547963125482,0.0,61.297717114285206 +25.945346863752462,0.0,61.22006049427628 +26.335216801176976,0.0,61.14241747845827 +26.725091909785156,0.0,61.06479777274515 +27.11497465583384,0.0,60.987211480834276 +27.504867505579874,0.0,60.90966846775295 +27.894772766166746,0.0,60.83217859852856 +28.28469306296462,0.0,60.754751897301716 +28.674630703116996,0.0,60.67739814954312 +29.064588232437373,0.0,60.60012729983674 +29.45456803762592,0.0,60.52294937232328 +29.844572505382764,0.0,60.44587415247338 +30.234604101964784,0.0,60.36891158487103 +30.624665373185458,0.0,60.292071693656894 +31.014758626188275,0.0,60.2153642643017 +31.40488632723008,0.0,60.138799320946035 +31.79505062434101,0.0,60.062385296597185 +32.18524897170755,0.0,59.98611558805132 +32.57547643681604,0.0,59.90997436353078 +32.965727768926136,0.0,59.83394547303109 +33.3559979559675,0.0,59.75801300521789 +33.74628182675645,0.0,59.68216096920007 +34.13657428966597,0.0,59.60637329452992 +34.5268701735124,0.0,59.530633990316346 +34.91716446622538,0.0,59.4549269861116 +35.30745191706457,0.0,59.37923637058128 +35.6977275935163,0.0,59.30354607327769 +36.087986165283546,0.0,59.227840103309674 +36.47822262029597,0.0,59.1521024697862 +36.868431866926585,0.0,59.07631710225955 +37.25861820123565,0.0,59.00051399359502 +37.64881535525211,0.0,58.92486872536776 +38.0390630277553,0.0,58.84958536044145 +38.42940107663788,0.0,58.77486788212312 +38.819868962009174,0.0,58.70092043283316 +39.21050662131854,0.0,58.62794715499189 +39.601353514675274,0.0,58.55615211146305 +39.99244949997207,0.0,58.48573944466699 +40.38383411687489,0.0,58.41691313791077 +40.77554722327643,0.0,58.34987733361467 +41.16762843839934,0.0,58.28483617419917 +41.560117381466306,0.0,58.22199364297121 +41.95305383081329,0.0,58.16155396190787 +42.34646698373894,0.0,58.10369828155129 +42.74032414245106,0.0,58.04847274477126 +43.1345700150626,0.0,57.99587401018752 +43.52914923012985,0.0,57.94589881597656 +43.92400649576576,0.0,57.898543741201465 +44.31908636096995,0.0,57.85380536492529 +44.71433353385536,0.0,57.81168050488124 +45.10970704273592,0.0,57.77215197682811 +45.505213331702066,0.0,57.73515860168513 +45.90086831208818,0.0,57.700629653570914 +46.29668797478536,0.0,57.668494724830694 +46.69268831068466,0.0,57.63868332825311 +47.088885310677156,0.0,57.611124897070056 +47.48529480654058,0.0,57.58574854628682 +47.88191966231513,0.0,57.56243828227559 +48.27873831814269,0.0,57.540993860892925 +48.675726350124954,0.0,57.52120572986475 +49.072859573033625,0.0,57.50286433691703 +49.470113642527075,0.0,57.485760050218985 +49.867464373377004,0.0,57.469683397053274 +50.264887421241795,0.0,57.45442474558912 +50.662358521336486,0.0,57.439774702665815 +51.059853329319424,0.0,57.425523636452624 +51.45734765996234,0.0,57.41146191511881 +51.85481716892359,0.0,57.39738014550365 +52.252237670974864,0.0,57.383068616219745 +52.6495847422179,0.0,57.368317934106344 +53.0468361067845,0.0,57.35293111684359 +53.44399319669476,0.0,57.33686496515858 +53.84107303707653,0.0,57.32017858965861 +54.23809313039761,0.0,57.30293277164108 +54.6350708200125,0.0,57.285188292403404 +55.03202352883239,0.0,57.267006171913025 +55.428968679768445,0.0,57.24844711191069 +55.825923616175146,0.0,57.22957205280716 +56.222905840520355,0.0,57.21044177589981 +56.61993269615854,0.0,57.19111714204274 +57.01702160600091,0.0,57.17165901209006 +57.41418999295861,0.0,57.152128326452484 +57.81145520038615,0.0,57.13258578687082 +58.20883473075135,0.0,57.11309233375577 +58.60632516311732,0.0,57.09377963339951 +59.00385099820236,0.0,57.07502510265404 +59.401320825390286,0.0,57.0572595408983 +59.79864363184835,0.0,57.040913906624525 +60.19572808651707,0.0,57.02641899921166 +60.592483017450355,0.0,57.01420561803856 +60.9888166162487,0.0,57.00466892109512 +61.38456555306445,0.0,56.99356567372321 +61.77942464850382,0.0,56.96747100574842 +62.17307201627186,0.0,56.91188030384387 +62.56194948421307,0.0,56.81334188723669 +62.93105616448062,0.0,56.66212685006391 +63.26286333553133,0.0,56.44932866378102 +63.54049718634593,0.0,56.1689190806801 +63.75127471271653,0.0,55.83328730217937 +63.88416418871931,0.0,55.46207968931748 +63.92823476629064,0.0,55.07491905435815 +63.88394365762451,0.0,54.6866120873119 +63.77368256539719,0.0,54.30268901111988 +63.622337691735694,0.0,53.92762457035579 +63.45032669961374,0.0,53.56469634079292 +63.262873598342004,0.0,53.213111062854736 +63.061976215067894,0.0,52.87121085505328 +62.84963245649551,0.0,52.53733815412728 +62.62784022932895,0.0,52.20983515814548 +62.39859728115898,0.0,51.88704414473327 +62.16389539282593,0.0,51.56731351737983 +61.92498607033715,0.0,51.249727101450276 +61.681688401820495,0.0,50.934791991172034 +61.43365727043279,0.0,50.623178212836706 +61.180547877557586,0.0,50.31555579273595 +60.92201526546503,0.0,50.012594836718065 +60.65771431731198,0.0,49.71496521196134 +60.38730023448195,0.0,49.423337024314094 +60.11042805924512,0.0,49.13838030006798 +59.82675267475834,0.0,48.86076506551461 +59.53592936196179,0.0,48.59116126738897 +59.23761292445565,0.0,48.33023909109603 +58.93145864318008,0.0,48.078668403814106 +58.6171213217353,0.0,47.83711931139146 +58.294312726298585,0.0,47.6062044002026 +57.963459280631895,0.0,47.38581109755661 +57.625477398040104,0.0,47.17532928333587 +57.281293197742,0.0,46.97413937017879 +56.931832719399765,0.0,46.78162177072379 +56.578022082232195,0.0,46.597156579382585 +56.220787405458154,0.0,46.420124367906965 +55.860931575011534,0.0,46.25007031080305 +55.49845689803577,0.0,46.087613756762394 +55.13304482961621,0.0,45.933804137845456 +54.76437602927139,0.0,45.7896919203494 +54.39213115651987,0.0,45.65632765012808 +54.0159909504369,0.0,45.53476171392197 +53.635636070541054,0.0,45.42604465758495 +53.25094590891756,0.0,45.33067880194406 +52.86251332188619,0.0,45.24719926999762 +52.47109091556416,0.0,45.173700520337775 +52.07743137562531,0.0,45.10827677288657 +51.682287387743486,0.0,45.049022327122785 +51.28641171714922,0.0,44.99403148252517 +50.89055506059957,0.0,44.94140880138315 +50.49520533916393,0.0,44.890752522503135 +50.100314182385745,0.0,44.84470631409587 +49.7057676651107,0.0,44.806284737577045 +49.311452100854474,0.0,44.77850251347566 +48.917253723576124,0.0,44.7643741236507 +48.523058608121325,0.0,44.7669142886312 +48.12876181923969,0.0,44.788436357325736 +47.734316577608105,0.0,44.82653063769594 +47.339700209575035,0.0,44.876837503672505 +46.94489012104562,0.0,44.93499112376574 +46.54986379748169,0.0,44.996625825599295 +46.15459864478841,0.0,45.05737593679682 +45.75907206887091,0.0,45.11287570542524 +45.36330276554711,0.0,45.16005503951189 +44.96746257722856,0.0,45.200650422536626 +44.57175851037581,0.0,45.237512370057445 +44.17639788967611,0.0,45.27349147718901 +43.78158780114671,0.0,45.31143833904599 +43.38753556947483,0.0,45.35420355074302 +42.994447485110996,0.0,45.404629513057586 +42.602404616303986,0.0,45.46421236876341 +42.211224062264854,0.0,45.53161636133753 +41.82068950840242,0.0,45.605147490562885 +41.43058471968215,0.0,45.683112154005826 +41.04069330195621,0.0,45.76381635144931 +40.65079909974674,0.0,45.845566400902996 +40.26069073097625,0.0,45.92669455585161 +39.87033199735895,0.0,46.00645250623823 +39.47990404943699,0.0,46.08523350069264 +39.089601562386804,0.0,46.163501752395945 +38.699619131828086,0.0,46.24172155408603 +38.310151592050595,0.0,46.32035727805733 +37.92139353867406,0.0,46.39987321704773 +37.53341243575633,0.0,46.4804512376094 +37.14578679204914,0.0,46.56118845107177 +36.757977611099626,0.0,46.6409214206634 +36.36944597601162,0.0,46.71848655049952 +35.97965304944562,0.0,46.7927204833654 +35.58805983494879,0.0,46.86245962337625 +35.19412980232512,0.0,46.92653751060712 +34.79777456411199,0.0,46.9832049325106 +34.399879506512185,0.0,47.02944708900101 +34.0014577837437,0.0,47.0620828269915 +33.603522470467865,0.0,47.07793123206524 +33.20708672090267,0.0,47.073811230692016 +32.813163609709456,0.0,47.04654190845507 +32.42276899603307,0.0,46.99299111917745 +32.03701818485839,0.0,46.91186017974532 +31.657153692288773,0.0,46.80419088477862 +31.28442614920821,0.0,46.67117714125415 +30.92008634561393,0.0,46.514013333488734 +30.56538499194661,0.0,46.3338933684592 +30.221572798646797,0.0,46.13201155092568 +29.889931662370586,0.0,45.90954380805712 +29.572201964874765,0.0,45.667401143304645 +29.270472943922897,0.0,45.40629232705919 +28.986842588512467,0.0,45.126921356311314 +28.72340880808428,0.0,44.82999206893827 +28.48226959163584,0.0,44.51620830281729 +28.26551966634105,0.0,44.18627572562909 +28.07460163333341,0.0,43.841228733223076 +27.909511355665984,0.0,43.48283173347103 +27.770050100772103,0.0,43.11294722762126 +27.656019454311775,0.0,42.733437716922154 +27.56722068371832,0.0,42.34616554350869 +27.503455295095094,0.0,41.952993288185866 +27.464524635432085,0.0,41.55578337264538 +27.45023021083265,0.0,41.1563982185789 +27.46037344784346,0.0,40.756700327234746 +27.494755693454515,0.0,40.35855212030462 +27.553178374212465,0.0,39.963816099036855 +27.63544291666401,0.0,39.57435476467977 +27.741350826912495,0.0,39.1920304593684 +27.87057011496561,0.0,38.81857895057257 +28.020743596188495,0.0,38.4538100182895 +28.187939102510555,0.0,38.096035629052565 +28.36818293727842,0.0,37.743528368842505 +28.55750140383868,0.0,37.39456090319669 +28.751921044208018,0.0,37.047405818095854 +28.94746808217635,0.0,36.700335779077385 +29.140579810857886,0.0,36.351815183258225 +29.330803234562232,0.0,36.00175954145271 +29.519107990007797,0.0,35.65074850357307 +29.70647119224016,0.0,35.29936498135508 +29.893869876748248,0.0,34.94819196609123 +30.082280999464295,0.0,34.59781244907397 +30.272681595877195,0.0,34.248809421595766 +30.465824431217484,0.0,33.90162410495958 +30.661533764796708,0.0,33.5561109104556 +30.85939351522027,0.0,33.21197245524391 +31.05898783976359,0.0,32.868911356484524 +31.259900736588733,0.0,32.5266302313375 +31.461716124301134,0.0,32.184831776519516 +31.664018160176184,0.0,31.843218529633983 +31.866390762819314,0.0,31.50149318739759 +32.068418009949255,0.0,31.159358287413703 +32.26968397928478,0.0,30.816516526399038 +32.46977258943126,0.0,30.472670521513642 +32.66826791810748,0.0,30.127522810360876 +32.86475396347551,0.0,29.780776169214118 +33.05884360276934,0.0,29.43215501376154 +33.25141251627779,0.0,29.082343929165766 +33.44506308229882,0.0,28.733340663017554 +33.642522423992176,0.0,28.38723755579065 +33.84651782363089,0.0,28.04612686840219 +34.05977616570466,0.0,27.712100941325904 +34.28502473248654,0.0,27.38725219459225 +34.524904646373805,0.0,27.073657693793983 +34.780656752779734,0.0,26.77314636726385 +35.0523811339977,0.0,26.487344910274363 +35.340144935858895,0.0,26.21787413090431 +35.64401514508115,0.0,25.966354916789165 +35.96405890749562,0.0,25.7344080760077 +36.300340823119996,0.0,25.52365425752536 +36.65223764498575,0.0,25.33563566742901 +37.017483599074176,0.0,25.171708190079634 +37.393573048000405,0.0,25.033200103673053 +37.778000513492934,0.0,24.921439845518442 +38.16826035816693,0.0,24.837755932481624 +38.561846944637566,0.0,24.783476642758433 +38.95627181976111,0.0,24.759894931382313 +39.349814331835454,0.0,24.766701482012497 +39.741817899646485,0.0,24.80136790405595 +40.131703987075404,0.0,24.86120271574203 +40.5188939784467,0.0,24.943514594413415 +40.90280925808485,0.0,25.045611978742798 +41.282871369427724,0.0,25.164803546072864 +41.658390476572336,0.0,25.298653668890132 +42.02683596133883,0.0,25.448962635125447 +42.38416332163576,0.0,25.621013803366747 +42.72628318540863,0.0,25.820193717205576 +43.04971025441353,0.0,26.050212263370955 +43.35357624713217,0.0,26.307515724881004 +43.637721493323816,0.0,26.586583902935224 +43.90235681816931,0.0,26.88206875937131 +44.150680718109996,0.0,27.19001219064363 +44.387333733824,0.0,27.50712675595149 +44.61696595279011,0.0,27.830129469667906 +44.84422714426041,0.0,28.15573726660917 +45.073767316157,0.0,28.48066724070494 +45.31023639684532,0.0,28.801636247214844 +45.557673319449805,0.0,29.11535859558503 +45.81744168532863,0.0,29.41853690043084 +46.09017357224089,0.0,29.707870355430725 +46.37646374586653,0.0,29.980142166108774 +46.67516078249155,0.0,30.23610509769551 +46.98264747890987,0.0,30.482116046510953 +47.295123572013075,0.0,30.724948228939702 +47.609992093356865,0.0,30.968908604534178 +47.92760508121485,0.0,31.212257109764238 +48.24875834097712,0.0,31.452344348338755 +48.57424783714711,0.0,31.68652052618318 +48.90486937511489,0.0,31.91213608789302 +49.24141876027055,0.0,32.126541478063785 +49.58468145563679,0.0,32.32711315632268 +49.93493304552547,0.0,32.51250462599606 +50.29171830665935,0.0,32.68320054632973 +50.654525371410735,0.0,32.83982671010571 +51.02284269037863,0.0,32.98300898966269 +51.39615839593535,0.0,33.11337317778265 +51.77396093867989,0.0,33.23154514680428 +52.155738450984565,0.0,33.338150689509575 +52.540979383448374,0.0,33.433815678237224 +52.9291718684436,0.0,33.51916590576921 +53.31980419745595,0.0,33.594827324000896 +53.71236482108438,0.0,33.66142572571427 +54.106341871701204,0.0,33.71958690369135 +54.50122395901878,0.0,33.769936889384134 +54.89661242455367,0.0,33.81319614801434 +55.29239342270826,0.0,33.85032270102626 +55.68849718228117,0.0,33.882311643273326 +56.0848540911844,0.0,33.91015814916571 +56.48139437821661,0.0,33.93485731355683 +56.87804835173311,0.0,33.95740415174349 +57.274747036099285,0.0,33.97878683714869 +57.671455108152756,0.0,33.99962280910385 +58.06818696765116,0.0,34.01998486196388 +58.46496099218572,0.0,34.03990203391403 +58.861795718461025,0.0,34.059403442696286 +59.25870936495495,0.0,34.07851820605259 +59.65572038881544,0.0,34.09727528261155 +60.05284613339693,0.0,34.11568811745076 +60.450084768896005,0.0,34.133479932908266 +60.84741728126806,0.0,34.150118813075046 +61.24482433824177,0.0,34.1650640112515 +61.64228644843253,0.0,34.17777478073796 +62.03978420001233,0.0,34.18771037483484 +62.43729810159655,0.0,34.19433004684248 +62.83481017337732,0.0,34.197182551317276 +63.23231524417094,0.0,34.19660870904208 +63.629814666440865,0.0,34.1933628763809 +64.02731003132051,0.0,34.18820330797459 +64.42480285038665,0.0,34.181887940237374 +64.82229463521605,0.0,34.175174948253456 +65.2197868973855,0.0,34.16882234799375 +65.61728090980172,0.0,34.163477173871655 +66.01477667246472,0.0,34.15925541951496 +66.41227386714782,0.0,34.1561149198875 +66.80977201651099,0.0,34.15401327128312 +67.20727096144088,0.0,34.152908069995604 +67.60477014504077,0.0,34.1527571509888 +68.00226940819735,0.0,34.15351811055655 +68.39976827357057,0.0,34.15514854499264 +68.79726642293373,0.0,34.15760620970427 +69.19476345850349,0.0,34.160848700985234 +69.59225914160982,0.0,34.16483385379938 +69.9897529949127,0.0,34.16951910532718 +70.38724470018543,0.0,34.17486229053249 +70.78473393920133,0.0,34.18082108526577 +71.18222031417704,0.0,34.18735300626419 +71.57970358644253,0.0,34.19441588849158 +71.97718319910113,0.0,34.20196732824176 +72.37465899303946,0.0,34.2099650809219 +72.7721304909175,0.0,34.21836666326914 +73.16959745406525,0.0,34.22712983069064 +73.56705940514264,0.0,34.236212259036925 +73.96451602592302,0.0,34.245571624158444 +74.3619669981797,0.0,34.255165522349046 +74.75941200368595,0.0,34.264951709015904 +75.15685056510178,0.0,34.27488786000947 +75.55428244375717,0.0,34.2849315716236 +75.95170724186875,0.0,34.29504059926545 +76.34912487987984,0.0,34.30518025622601 +76.74653623291385,0.0,34.31533709742774 +77.14394217609416,0.0,34.32550133739994 +77.54134366410084,0.0,34.33566319067201 +77.93874157205727,0.0,34.34581287177324 +78.33613701375688,0.0,34.355940436119674 +78.73353078476637,0.0,34.36603625735397 +79.13092383976583,0.0,34.376090470448794 +79.52831713343528,0.0,34.38609321037684 +79.92571162045482,0.0,34.39603477122412 +80.32310825550451,0.0,34.40590528796328 +80.72050791370772,0.0,34.41569497512369 +81.11791162930122,0.0,34.42539396767802 +81.51532019785172,0.0,34.43499255971227 +81.9127347331526,0.0,34.44448096575579 +82.3101560307706,0.0,34.45384924122458 +82.7075850453858,0.0,34.463087759761336 +83.10502281123492,0.0,34.47218657678204 +83.50247020344133,0.0,34.48113590681605 +83.89992817668514,0.0,34.48992604394938 +84.29739768564637,0.0,34.498547043597995 +84.69487960544845,0.0,34.50698927940465 +85.09237489077144,0.0,34.51524280678528 +85.48988449629536,0.0,34.523297840269265 +85.887409456257,0.0,34.531144594385935 +86.28495056622305,0.0,34.53877328366464 +86.68250886043023,0.0,34.54617412263471 +87.08008354331189,0.0,34.55340566500675 +87.47766570452069,0.0,34.560886697102205 +87.87524341055585,0.0,34.56915446512714 +88.2728047279166,0.0,34.57874621528761 +88.67033796177212,0.0,34.590199193789644 +89.06783109906495,0.0,34.60405056728268 +89.46527228585094,0.0,34.620836627292675 +89.86261482236368,0.0,34.640045665305315 +90.25970961939977,0.0,34.65809118698984 +90.65638897149465,0.0,34.67082598259127 +91.05248533229707,0.0,34.67410268324119 +91.44783083722908,0.0,34.66377415874129 +91.84225793993944,0.0,34.635693199336515 +92.23558755835948,0.0,34.585730177296355 +92.62676580525513,0.0,34.511119304918516 +93.01325800505626,0.0,34.41140337000897 +93.39238620062643,0.0,34.28634847595204 +93.76147235527262,0.0,34.13572072613199 +94.11783851185835,0.0,33.95928614437648 +94.45880671324726,0.0,33.756810834069796 +94.78173209787849,0.0,33.52811054195956 +95.08473760563268,0.0,33.27415593900095 +95.36671922857246,0.0,32.99708041691049 +95.62660708857264,0.0,32.69906836323143 +95.86333106883808,0.0,32.38230408595041 +96.07582113213027,0.0,32.04897221128071 +96.26300835500417,0.0,31.701256967652284 +96.42508733307949,0.0,31.341358017489416 +96.56600344083435,0.0,30.97151989317944 +96.69039491180344,0.0,30.593995480560235 +96.80289997952137,0.0,30.211037585913 +96.90815671840947,0.0,29.824899174632293 +97.01080336200238,0.0,29.43783313255599 +97.11545316303975,0.0,29.0520797755678 +97.22474175450846,0.0,28.668894826178654 +97.33792337216515,0.0,28.28785003082316 +97.45392105734084,0.0,27.908352055841487 +97.57165769225324,0.0,27.52980780624383 +97.69005631823343,0.0,27.151623948370364 +97.80803989705574,0.0,26.773207307674603 +97.92455867843307,0.0,26.393979825377755 +98.03920915092502,0.0,26.013726141568696 +98.1522466914487,0.0,25.632600516634437 +98.26395627200324,0.0,25.250773679193124 +98.37462294414445,0.0,24.86841635786287 +98.48453167987145,0.0,24.485699440375143 +98.59396753074006,0.0,24.102793814461414 +98.7032153891927,0.0,23.71987004962648 +98.81256038634189,0.0,23.33709919271513 +98.92228749418669,0.0,22.954651892788835 +99.03268168472627,0.0,22.57269895802239 +99.14402792995978,0.0,22.191411196590586 +99.25661128144296,0.0,21.810959496224903 +99.37071671117498,0.0,21.431514585543464 +99.48640046572294,0.0,21.052978848509706 +99.60242106322018,0.0,20.673733306848312 +99.7170803665027,0.0,20.291623008984637 +99.82856265364533,0.0,19.90452673537297 +99.92456074615865,0.0,19.51339216509026 +99.9741168358215,0.0,19.124622098656253 +99.94435890132749,0.0,18.745180847581715 +99.81512799800026,0.0,18.38165260159859 +99.6056898082029,0.0,18.03944188410629 +99.34292971367327,0.0,17.723725447752262 +99.05325511966383,0.0,17.439388788207758 +98.75137048586151,0.0,17.18418474771529 +98.43986673440357,0.0,16.94848330935515 +98.12076953727264,0.0,16.722354288884176 +97.79564632002055,0.0,16.499431879635093 +97.4652580422151,0.0,16.27962562567183 +97.13028340182514,0.0,16.063483354237825 +96.79140117637624,0.0,15.851552813019847 +96.44929014339395,0.0,15.64438174970465 +96.10462915996052,0.0,15.442517911979003 +95.758084513204,0.0,15.24647778175758 +95.41001349213835,0.0,15.055993491725724 +95.06044974923584,0.0,14.869975911043671 +94.70941142341769,0.0,14.687297005659044 +94.3569167331618,0.0,14.506828821076127 +94.00298389694605,0.0,14.327443402799226 +93.64763113324832,0.0,14.148013432785994 +93.29058611958035,0.0,13.968932875676217 +92.93065805167552,0.0,13.795409590776108 +92.5664747360551,0.0,13.633601344055638 +92.19671887334398,0.0,13.489446881966742 +91.82148306750838,0.0,13.363248997203083 +91.44235877021512,0.0,13.249318512592808 +91.06100489718888,0.0,13.14169631517594 +90.67858456697441,0.0,13.036295658268175 +90.29536413530954,0.0,12.932417556949279 +89.91151576283254,0.0,12.829719360632906 +89.52721137151161,0.0,12.72785865740274 +89.14262304242827,0.0,12.626492876229133 +88.7579228566641,0.0,12.525279525639089 +88.37327963347708,0.0,12.423882558250053 +87.9887769869295,0.0,12.322138007761023 +87.60440704091081,0.0,12.220066956690076 +87.22015722546686,0.0,12.11769947745923 +86.83601528887016,0.0,12.01506588116053 +86.45196858160986,0.0,11.912196240215982 +86.0680046928451,0.0,11.809120786160953 +85.68411129129174,0.0,11.705869670974133 +85.30027572743894,0.0,11.602473126190887 +84.91648567000252,0.0,11.498961303789903 +84.53272870814165,0.0,11.395364355749876 +84.14899219234549,0.0,11.291712593162828 +83.76526387088654,0.0,11.188036008894123 +83.38153109425397,0.0,11.084364914035778 +82.99778304274037,0.0,10.9807260396296 +82.61401717053224,0.0,10.877125431982662 +82.23023443230964,0.0,10.77356134084817 +81.84643562363931,0.0,10.670032015979345 +81.46262177875796,0.0,10.566535786686075 +81.07879353411897,0.0,10.463070823164905 +80.6949519239591,0.0,10.35963553428239 +80.31109774384502,0.0,10.256228010678408 +79.9272318689002,0.0,10.152846661219513 +79.54335525380463,0.0,10.049489656102256 +79.1594686145684,0.0,9.94615532463652 +78.77557298542823,0.0,9.84284191657552 +78.39166908239416,0.0,9.739547681672471 +78.00775786014627,0.0,9.636270869680594 +77.62384011425128,0.0,9.53300980990978 +77.23991679938925,0.0,9.429762752113234 +76.85598879068357,0.0,9.3265278664875 +76.47205688370096,0.0,9.223303561899153 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv b/gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv new file mode 100644 index 00000000..b5e9f738 --- /dev/null +++ b/gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv @@ -0,0 +1,865 @@ +# x_m, y_m, w_tr_right_m, w_tr_left_m +0.0, 0.0, 1.1, 1.1 +-0.383936998609612, -0.10320847281061823, 1.1, 1.1 +-0.7678753496826622, -0.20641169488089267, 1.1, 1.1 +-1.151814018982386, -0.3096112573442502, 1.1, 1.1 +-1.5357522109420796, -0.41280906956082436, 1.1, 1.1 +-1.9196891299950265, -0.5160067226640551, 1.1, 1.1 +-2.3036237419044885, -0.6192059669007194, 1.1, 1.1 +-2.6875553306604, -0.7224086320742855, 1.1, 1.1 +-3.0714830211393926, -0.8256163093181935, 1.1, 1.1 +-3.455406017774737, -0.9288305102091988, 1.1, 1.1 +-3.8393244796797763, -1.0320512347473079, 1.1, 1.1 +-4.223238645524531, -1.1352782442625122, 1.1, 1.1 +-4.607148594865655, -1.2385113796414555, 1.1, 1.1 +-4.991054566373195, -1.3417504817708008, 1.1, 1.1 +-5.374956798717146, -1.4449953119805332, 1.1, 1.1 +-5.75885553056753, -1.5482455520439593, 1.1, 1.1 +-6.142750921037678, -1.651501201961079, 1.1, 1.1 +-6.5266431292409575, -1.754761863948541, 1.1, 1.1 +-6.910532393847366, -1.8580274584496597, 1.1, 1.1 +-7.294418953526939, -1.961297746794434, 1.1, 1.1 +-7.67830296739299, -2.0645725698695068, 1.1, 1.1 +-8.062184674115569, -2.1678516890048765, 1.1, 1.1 +-8.446064232807995, -2.2711347859738362, 1.1, 1.1 +-8.82994180258362, -2.3744218607764065, 1.1, 1.1 +-9.213817781225814, -2.4777125951858805, 1.1, 1.1 +-9.597692168734559, -2.5810067505322563, 1.1, 1.1 +-9.98156520377988, -2.6843042472588556, 1.1, 1.1 +-10.365437204588462, -2.787604767138985, 1.1, 1.1 +-10.749308250716984, -2.8909081510593153, 1.1, 1.1 +-11.133178580835468, -2.9942142399064884, 1.1, 1.1 +-11.517048433613908, -3.097522715453825, 1.1, 1.1 +-11.900917968165663, -3.200833498144647, 1.1, 1.1 +-12.284787423160738, -3.3041462697522674, 1.1, 1.1 +-12.66865703726917, -3.4074609507200213, 1.1, 1.1 +-13.052526890047611, -3.5107772228212153, 1.1, 1.1 +-13.436397220166082, -3.6140949269425, 1.1, 1.1 +-13.820268345851282, -3.717413903970537, 1.1, 1.1 +-14.204140346659866, -3.8207338356786416, 1.1, 1.1 +-14.588013461261864, -3.9240546425101406, 1.1, 1.1 +-14.971887928327275, -4.027376085795013, 1.1, 1.1 +-15.35576382741279, -4.130697926863244, 1.1, 1.1 +-15.739641556301772, -4.23402000660149, 1.1, 1.1 +-16.123521194550875, -4.337342086339743, 1.1, 1.1 +-16.507402980830108, -4.440663927407974, 1.1, 1.1 +-16.89128707425285, -4.543985370692847, 1.1, 1.1 +-17.275173713489085, -4.647306257081011, 1.1, 1.1 +-17.659063057652162, -4.750626347902459, 1.1, 1.1 +-18.042955424968785, -4.853945404487168, 1.1, 1.1 +-18.42685089499561, -4.957263267721802, 1.1, 1.1 +-18.81074970640267, -5.060579619379668, 1.1, 1.1 +-19.19465209785997, -5.163894459460765, 1.1, 1.1 +-19.578558228480837, -5.2672074697384, 1.1, 1.1 +-19.962468336935316, -5.370518411542572, 1.1, 1.1 +-20.346382582336737, -5.473827125759918, 1.1, 1.1 +-20.73030120335512, -5.577133373720441, 1.1, 1.1 +-21.114224359103808, -5.6804370758674505, 1.1, 1.1 +-21.498152288252808, -5.783737834417602, 1.1, 1.1 +-21.882085229472157, -5.887035649370888, 1.1, 1.1 +-22.266023341875172, -5.99033012294395, 1.1, 1.1 +-22.6499668641319, -6.093621175580118, 1.1, 1.1 +-23.033915955355663, -6.196908568609368, 1.1, 1.1 +-23.417870774659807, -6.300192142918365, 1.1, 1.1 +-23.80183164027103, -6.403471580280422, 1.1, 1.1 +-24.185797517952583, -6.506746562468837, 1.1, 1.1 +-24.569763156964118, -6.61001565746353, 1.1, 1.1 +-24.953722113215207, -6.713277353687727, 1.1, 1.1 +-25.337668022172096, -6.816529980451313, 1.1, 1.1 +-25.72159451930101, -6.919772105734195, 1.1, 1.1 +-26.105495160511513, -7.0230020588462585, 1.1, 1.1 +-26.4893637403832, -7.126218248654065, 1.1, 1.1 +-26.873193735268973, -7.22941924313752, 1.1, 1.1 +-27.256978780635052, -7.332603371606509, 1.1, 1.1 +-27.64071259150436, -7.435769042927594, 1.1, 1.1 +-28.0243886442298, -7.538914665967332, 1.1, 1.1 +-28.408000733390935, -7.642038808705627, 1.1, 1.1 +-28.79154241489736, -7.745139800452367, 1.1, 1.1 +-29.17500939268876, -7.848217322980869, 1.1, 1.1 +-29.55847652959351, -7.951318473840951, 1.1, 1.1 +-29.94211956630006, -8.054550734096505, 1.1, 1.1 +-30.326120767143983, -8.158025323974991, 1.1, 1.1 +-30.710662476017525, -8.26185370237389, 1.1, 1.1 +-31.095926877699572, -8.366147169077333, 1.1, 1.1 +-31.48209623652569, -8.471017103426139, 1.1, 1.1 +-31.869050581034482, -8.576336851198471, 1.1, 1.1 +-32.25220171883802, -8.678462955486445, 1.1, 1.1 +-32.62487206067143, -8.77238422107705, 1.1, 1.1 +-32.99993594453883, -8.872591895776262, 1.1, 1.1 +-33.396885789318524, -8.994200872141919, 1.1, 1.1 +-33.801994329925826, -9.095399186520948, 1.1, 1.1 +-34.19315706327043, -9.120088008544716, 1.1, 1.1 +-34.55016524219926, -9.020283527059233, 1.1, 1.1 +-34.866458066641975, -8.806431214872264, 1.1, 1.1 +-35.14145349998617, -8.5145717559795, 1.1, 1.1 +-35.374622808589685, -8.180804785870604, 1.1, 1.1 +-35.570474548611806, -7.832287054091635, 1.1, 1.1 +-35.74433809739808, -7.476964362815932, 1.1, 1.1 +-35.912944541298174, -7.120294140629777, 1.1, 1.1 +-36.08998295819422, -6.766799104780075, 1.1, 1.1 +-36.277394451326494, -6.4173916907380635, 1.1, 1.1 +-36.47428400813493, -6.072112790633152, 1.1, 1.1 +-36.67975685472948, -5.731003296594757, 1.1, 1.1 +-36.89291789899339, -5.394104180308963, 1.1, 1.1 +-37.112872367036594, -5.061456254348504, 1.1, 1.1 +-37.338724768959004, -4.733099058379374, 1.1, 1.1 +-37.56950013774517, -4.408787000955076, 1.1, 1.1 +-37.80404903859795, -4.087652277897383, 1.1, 1.1 +-38.04119944262535, -3.7687452212125345, 1.1, 1.1 +-38.27977892315199, -3.4511160037934525, 1.1, 1.1 +-38.51861537172921, -3.133814878089733, 1.1, 1.1 +-38.75653652079499, -2.815892096550947, 1.1, 1.1 +-38.99238855993523, -2.4964124704976745, 1.1, 1.1 +-39.22571507252263, -2.1749954803676945, 1.1, 1.1 +-39.45695696163346, -1.8519738321633459, 1.1, 1.1 +-39.68661416139457, -1.5277270907667706, 1.1, 1.1 +-39.9151865263762, -1.202635059730125, 1.1, 1.1 +-40.14317391114858, -0.8770773834922285, 1.1, 1.1 +-40.37107624983858, -0.5514336269352162, 1.1, 1.1 +-40.59930604379055, -0.22601740246014637, 1.1, 1.1 +-40.82792646100209, 0.09912276036306099, 1.1, 1.1 +-41.05691331624487, 0.4240044435589187, 1.1, 1.1 +-41.286242424290634, 0.7486451495952746, 1.1, 1.1 +-41.515889599911084, 1.0730624604966286, 1.1, 1.1 +-41.74583065787791, 1.3972739582875062, 1.1, 1.1 +-41.976041492519535, 1.721297224992421, 1.1, 1.1 +-42.20649783905095, 2.0451497630792006, 1.1, 1.1 +-42.4371755122439, 2.368849234129043, 1.1, 1.1 +-42.668050406426744, 2.692413140609789, 1.1, 1.1 +-42.89909825681454, 3.015859064545952, 1.1, 1.1 +-43.13029495773565, 3.339204587962038, 1.1, 1.1 +-43.36161624440513, 3.6624672133258946, 1.1, 1.1 +-43.59303801115135, 3.9856646022187006, 1.1, 1.1 +-43.82453599318935, 4.308814336664981, 1.1, 1.1 +-44.056086005290844, 4.6319338395758995, 1.1, 1.1 +-44.28766402134088, 4.955040772532635, 1.1, 1.1 +-44.519245696997835, 5.278152717559711, 1.1, 1.1 +-44.75080692659007, 5.601287256681635, 1.1, 1.1 +-44.982323524889345, 5.924461892366256, 1.1, 1.1 +-45.21377122711063, 6.247694206638079, 1.1, 1.1 +-45.44512600713902, 6.571001781521618, 1.1, 1.1 +-45.676363520632876, 6.894402199041385, 1.1, 1.1 +-45.90745966192057, 7.217912961665234, 1.1, 1.1 +-46.13839024577383, 7.541551730974336, 1.1, 1.1 +-46.36913108696434, 7.865336009436534, 1.1, 1.1 +-46.59965807982051, 8.189283458633026, 1.1, 1.1 +-46.82988578047659, 8.513449370450843, 1.1, 1.1 +-47.0592528370549, 8.838184271586845, 1.1, 1.1 +-47.28697450254276, 9.163976878677182, 1.1, 1.1 +-47.512264836577444, 9.491316863038044, 1.1, 1.1 +-47.73433766012617, 9.820693816428953, 1.1, 1.1 +-47.95240703282619, 10.15259733060945, 1.1, 1.1 +-48.16568685520139, 10.487516997339048, 1.1, 1.1 +-48.373634152965366, 10.82578894355699, 1.1, 1.1 +-48.576737324527514, 11.167098363512139, 1.1, 1.1 +-48.77575828413569, 11.510957574805092, 1.1, 1.1 +-48.971458946037664, 11.856879054149793, 1.1, 1.1 +-49.164601383594594, 12.204375119146851, 1.1, 1.1 +-49.355947431497626, 12.552958166953532, 1.1, 1.1 +-49.546258447097856, 12.90214107206714, 1.1, 1.1 +-49.73607430197151, 13.251576012717667, 1.1, 1.1 +-49.92540732740276, 13.601247634467406, 1.1, 1.1 +-50.11419268470392, 13.951189112448603, 1.1, 1.1 +-50.302365535187306, 14.301433542236794, 1.1, 1.1 +-50.48986104016521, 14.652014178520885, 1.1, 1.1 +-50.676614440506654, 15.002964196433105, 1.1, 1.1 +-50.86256089752392, 15.354316691548998, 1.1, 1.1 +-51.047635572529366, 15.706104918557475, 1.1, 1.1 +-51.23177362683526, 16.058361893477418, 1.1, 1.1 +-51.41491030131063, 16.411120950554384, 1.1, 1.1 +-51.596980677711066, 16.764415264920615, 1.1, 1.1 +-51.77792007646227, 17.118277852594993, 1.1, 1.1 +-51.957663579319885, 17.47274196826641, 1.1, 1.1 +-52.13616496385746, 17.82783124026644, 1.1, 1.1 +-52.31345963279404, 18.183527529673892, 1.1, 1.1 +-52.489605582943504, 18.5398011618501, 1.1, 1.1 +-52.66466065200644, 18.89662230304305, 1.1, 1.1 +-52.83868275724002, 19.25396143772743, 1.1, 1.1 +-53.011729815901504, 19.611788811707918, 1.1, 1.1 +-53.18385974524809, 19.970074670789177, 1.1, 1.1 +-53.355130382980335, 20.328789419889223, 1.1, 1.1 +-53.52559972591214, 20.687903304812732, 1.1, 1.1 +-53.69532561174403, 21.047386650921034, 1.1, 1.1 +-53.86436595773325, 21.407209783575478, 1.1, 1.1 +-54.03277868113701, 21.767343028137397, 1.1, 1.1 +-54.200621619655855, 22.127756630411476, 1.1, 1.1 +-54.36795284966036, 22.488420915759036, 1.1, 1.1 +-54.53483004973773, 22.84930620954143, 1.1, 1.1 +-54.70131129625851, 23.210382837120008, 1.1, 1.1 +-54.86745442692327, 23.5716211238561, 1.1, 1.1 +-55.03331743854589, 23.932991315554386, 1.1, 1.1 +-55.19895808927025, 24.29446373757619, 1.1, 1.1 +-55.364434296353586, 24.65600871528287, 1.1, 1.1 +-55.52980405660976, 25.017596574035757, 1.1, 1.1 +-55.69512528729603, 25.379197639196196, 1.1, 1.1 +-55.86045582611291, 25.74078215656886, 1.1, 1.1 +-56.02585351076098, 26.102320451515087, 1.1, 1.1 +-56.19137641761077, 26.46378284939622, 1.1, 1.1 +-56.35708230480617, 26.825139675573613, 1.1, 1.1 +-56.52302916916109, 27.18636117585191, 1.1, 1.1 +-56.689257345908224, 27.54742642682639, 1.1, 1.1 +-56.85565625127349, 27.908390004374045, 1.1, 1.1 +-57.02203773372758, 28.269344989801123, 1.1, 1.1 +-57.188213164401176, 28.630384941753903, 1.1, 1.1 +-57.3539937553116, 28.99160325976532, 1.1, 1.1 +-57.51919087758952, 29.35309350248166, 1.1, 1.1 +-57.68361574325229, 29.71494906943585, 1.1, 1.1 +-57.847264294909614, 30.07717783673841, 1.1, 1.1 +-58.010995585505825, 30.439387112656348, 1.1, 1.1 +-58.17592094219218, 30.801067098035418, 1.1, 1.1 +-58.34315169211994, 31.161707993721425, 1.1, 1.1 +-58.513799082883686, 31.5208000801168, 1.1, 1.1 +-58.68897444163469, 31.877833637623993, 1.1, 1.1 +-58.8697893341942, 32.23229823063544, 1.1, 1.1 +-59.057475138731554, 32.58340330450141, 1.1, 1.1 +-59.253576368477084, 32.929624871612916, 1.1, 1.1 +-59.459688134704514, 33.26932080270309, 1.1, 1.1 +-59.677208884594386, 33.60101046854923, 1.1, 1.1 +-59.9037899460757, 33.92629240136197, 1.1, 1.1 +-60.133723525715354, 34.24952543164384, 1.1, 1.1 +-60.36123500247579, 34.57512551158792, 1.1, 1.1 +-60.58352445884239, 34.90518307230783, 1.1, 1.1 +-60.802320024844484, 35.238248829909665, 1.1, 1.1 +-61.01972963406355, 35.57257675411289, 1.1, 1.1 +-61.237861140524394, 35.90642057596695, 1.1, 1.1 +-61.45882263692187, 36.238034344748, 1.1, 1.1 +-61.68472205683744, 36.565671711948816, 1.1, 1.1 +-61.91730487365491, 36.88788474613889, 1.1, 1.1 +-62.15656193835704, 37.20466915125794, 1.1, 1.1 +-62.401953618037574, 37.51645692003494, 1.1, 1.1 +-62.65294012067696, 37.823680204312254, 1.1, 1.1 +-62.90898157469899, 38.12677107637551, 1.1, 1.1 +-63.16953834719739, 38.42616160851044, 1.1, 1.1 +-63.43407064615264, 38.72228411167266, 1.1, 1.1 +-63.70203867954515, 39.0155705785912, 1.1, 1.1 +-63.97290265535538, 39.30645316110839, 1.1, 1.1 +-64.24612286112041, 39.59536393150991, 1.1, 1.1 +-64.52115942526402, 39.88273512119474, 1.1, 1.1 +-64.79747271488002, 40.16899880244859, 1.1, 1.1 +-65.07452293794879, 40.45458712711376, 1.1, 1.1 +-65.35177356427434, 40.739929542105784, 1.1, 1.1 +-65.62889594524464, 41.025291528039105, 1.1, 1.1 +-65.90588729637611, 41.31068104058093, 1.1, 1.1 +-66.1827735531439, 41.59608360041699, 1.1, 1.1 +-66.45958049190966, 41.88148456911959, 1.1, 1.1 +-66.73633404814854, 42.16686930826111, 1.1, 1.1 +-67.0130599982222, 42.45222333852723, 1.1, 1.1 +-67.28978427760578, 42.7375320214903, 1.1, 1.1 +-67.56653266266096, 43.02278079827936, 1.1, 1.1 +-67.84333100930616, 43.30795503046675, 1.1, 1.1 +-68.12020525301647, 43.59304023873814, 1.1, 1.1 +-68.39718117015357, 43.87802178466594, 1.1, 1.1 +-68.6742846961926, 44.16288502982246, 1.1, 1.1 +-68.95154160749523, 44.44761557445006, 1.1, 1.1 +-69.22897815776328, 44.732197586771036, 1.1, 1.1 +-69.5066244989754, 45.016605131310286, 1.1, 1.1 +-69.78451253335706, 45.30080646495571, 1.1, 1.1 +-70.06267456091715, 45.58476968548181, 1.1, 1.1 +-70.34114280210775, 45.868462890663125, 1.1, 1.1 +-70.61994923871107, 46.15185433738752, 1.1, 1.1 +-70.89912609117923, 46.43491212342953, 1.1, 1.1 +-71.17870557996447, 46.717604505677, 1.1, 1.1 +-71.4587197664055, 46.999899422791124, 1.1, 1.1 +-71.73920087095456, 47.281765211216445, 1.1, 1.1 +-72.02018103450709, 47.56316996872749, 1.1, 1.1 +-72.30169239795866, 47.84408179309879, 1.1, 1.1 +-72.58376710220466, 48.12446894121821, 1.1, 1.1 +-72.86643720858396, 48.40429959041692, 1.1, 1.1 +-73.14963573037875, 48.683618292431305, 1.1, 1.1 +-73.43301158399541, 48.96268861851567, 1.1, 1.1 +-73.71616316735371, 49.24181312269366, 1.1, 1.1 +-73.99868879881666, 49.52129427943226, 1.1, 1.1 +-74.28018695586066, 49.80143464275512, 1.1, 1.1 +-74.56025595684872, 50.082536766685855, 1.1, 1.1 +-74.83847423097588, 50.36492977717658, 1.1, 1.1 +-75.11298516418756, 50.650866321395114, 1.1, 1.1 +-75.37955132946264, 50.9457899055102, 1.1, 1.1 +-75.63370371030787, 51.255443805230655, 1.1, 1.1 +-75.86246239701535, 51.585213052571234, 1.1, 1.1 +-76.02803271964164, 51.93943778221657, 1.1, 1.1 +-76.08812195356482, 52.32226862485863, 1.1, 1.1 +-76.00649139823248, 52.72013289402634, 1.1, 1.1 +-75.77804505101929, 53.02828150195576, 1.1, 1.1 +-75.4201704999323, 53.1514411174155, 1.1, 1.1 +-75.0107297007509, 53.18263504983921, 1.1, 1.1 +-74.6085742242518, 53.21589626238503, 1.1, 1.1 +-74.2141051156186, 53.25718999387664, 1.1, 1.1 +-73.82268533466674, 53.304887321454714, 1.1, 1.1 +-73.43081208068446, 53.35731469096692, 1.1, 1.1 +-73.03806330552675, 53.41267738344951, 1.1, 1.1 +-72.64453511365336, 53.46916023387394, 1.1, 1.1 +-72.25032345041079, 53.52494815676838, 1.1, 1.1 +-71.85552449981546, 53.57822606666105, 1.1, 1.1 +-71.46023428677049, 53.62717879852339, 1.1, 1.1 +-71.0645485179523, 53.67000526885789, 1.1, 1.1 +-70.66853855569569, 53.70579264440989, 1.1, 1.1 +-70.27223709779285, 53.73502900536222, 1.1, 1.1 +-69.87567381888243, 53.758325665182554, 1.1, 1.1 +-69.47887815493308, 53.77629401689524, 1.1, 1.1 +-69.08187962147011, 53.789545612638015, 1.1, 1.1 +-68.6847075749055, 53.79869160676523, 1.1, 1.1 +-68.28739168987791, 53.804343630971246, 1.1, 1.1 +-67.88996140235595, 53.80711307828047, 1.1, 1.1 +-67.49244614830832, 53.8076111826039, 1.1, 1.1 +-67.09487544326028, 53.806449496079246, 1.1, 1.1 +-66.69727880273716, 53.80423941173091, 1.1, 1.1 +-66.2996857422643, 53.801592322583254, 1.1, 1.1 +-65.9021256978103, 53.799119621660616, 1.1, 1.1 +-65.50462524130366, 53.79738584310758, 1.1, 1.1 +-65.10718214515754, 53.79650300271833, 1.1, 1.1 +-64.70977811133736, 53.79632933050334, 1.1, 1.1 +-64.31239484180855, 53.79672043110291, 1.1, 1.1 +-63.91501372030991, 53.797531988714056, 1.1, 1.1 +-63.51761636925017, 53.79861944886371, 1.1, 1.1 +-63.120184331481454, 53.79983841619221, 1.1, 1.1 +-62.72271100379994, 53.800867163517914, 1.1, 1.1 +-62.32525104163933, 53.80046866414782, 1.1, 1.1 +-61.92787859181795, 53.79711073613577, 1.1, 1.1 +-61.53066796026741, 53.78926135664895, 1.1, 1.1 +-61.133693452919395, 53.77538842329779, 1.1, 1.1 +-60.73702929614887, 53.75395983369285, 1.1, 1.1 +-60.340749716330826, 53.72344491746471, 1.1, 1.1 +-59.9448776257868, 53.683751229760475, 1.1, 1.1 +-59.54928827965508, 53.638922238434944, 1.1, 1.1 +-59.15383059981555, 53.59373969725898, 1.1, 1.1 +-58.758355258394815, 53.5528190070024, 1.1, 1.1 +-58.36275016004204, 53.51709941373493, 1.1, 1.1 +-57.9669394872488, 53.48393008914528, 1.1, 1.1 +-57.57085315058708, 53.450509206358774, 1.1, 1.1 +-57.174710726471574, 53.41389969215823, 1.1, 1.1 +-56.77921366607937, 53.37094012351148, 1.1, 1.1 +-56.38510860877728, 53.31844926777498, 1.1, 1.1 +-55.99283247980795, 53.254818886824154, 1.1, 1.1 +-55.60191549702318, 53.183042777783236, 1.1, 1.1 +-55.21172303685037, 53.10695183307941, 1.1, 1.1 +-54.821698361698814, 53.02990716299155, 1.1, 1.1 +-54.43170025847572, 52.95275644385991, 1.1, 1.1 +-54.041726260924236, 52.87551017716518, 1.1, 1.1 +-53.65177390278753, 52.79817822793472, 1.1, 1.1 +-53.26184079736546, 52.72077054075248, 1.1, 1.1 +-52.87192447840118, 52.643297060202514, 1.1, 1.1 +-52.48202247963787, 52.56576765131212, 1.1, 1.1 +-52.09213241437536, 52.48819225866531, 1.1, 1.1 +-51.70225181635681, 52.410580826846086, 1.1, 1.1 +-51.3123782193254, 52.33294314132509, 1.1, 1.1 +-50.922509157024294, 52.25528930579967, 1.1, 1.1 +-50.532642322310004, 52.17762910574049, 1.1, 1.1 +-50.14277508981236, 52.09997248573156, 1.1, 1.1 +-49.75290515238785, 52.02232946991356, 1.1, 1.1 +-49.363030043779666, 51.94470976420044, 1.1, 1.1 +-48.97314729773098, 51.867123472289556, 1.1, 1.1 +-48.58325444798495, 51.78958045920824, 1.1, 1.1 +-48.19334918739808, 51.71209058998384, 1.1, 1.1 +-47.8034288906002, 51.634663888757, 1.1, 1.1 +-47.41349125044783, 51.55731014099841, 1.1, 1.1 +-47.02353372112745, 51.48003929129203, 1.1, 1.1 +-46.633553915938904, 51.40286136377857, 1.1, 1.1 +-46.24354944818206, 51.32578614392866, 1.1, 1.1 +-45.85351785160004, 51.248823576326316, 1.1, 1.1 +-45.463456580379365, 51.17198368511218, 1.1, 1.1 +-45.07336332737655, 51.09527625575698, 1.1, 1.1 +-44.68323562633474, 51.018711312401315, 1.1, 1.1 +-44.293071329223814, 50.942297288052465, 1.1, 1.1 +-43.90287298185727, 50.8660275795066, 1.1, 1.1 +-43.51264551674878, 50.789886354986066, 1.1, 1.1 +-43.12239418463869, 50.71385746448638, 1.1, 1.1 +-42.73212399759732, 50.63792499667317, 1.1, 1.1 +-42.34184012680837, 50.56207296065536, 1.1, 1.1 +-41.95154766389885, 50.486285285985204, 1.1, 1.1 +-41.56125178005242, 50.410545981771634, 1.1, 1.1 +-41.17095748733944, 50.33483897756689, 1.1, 1.1 +-40.780670036500254, 50.25914836203657, 1.1, 1.1 +-40.390394360048525, 50.18345806473297, 1.1, 1.1 +-40.00013578828128, 50.107752094764955, 1.1, 1.1 +-39.60989933326885, 50.03201446124149, 1.1, 1.1 +-39.21969008663824, 49.95622909371483, 1.1, 1.1 +-38.829503752329174, 49.8804259850503, 1.1, 1.1 +-38.43930659831271, 49.80478071682304, 1.1, 1.1 +-38.049058925809526, 49.72949735189674, 1.1, 1.1 +-37.65872087692694, 49.6547798735784, 1.1, 1.1 +-37.26825299155565, 49.580832424288445, 1.1, 1.1 +-36.877615332246286, 49.507859146447174, 1.1, 1.1 +-36.48676843888955, 49.43606410291834, 1.1, 1.1 +-36.095672453592755, 49.36565143612228, 1.1, 1.1 +-35.704287836689936, 49.29682512936605, 1.1, 1.1 +-35.31257473028839, 49.22978932506996, 1.1, 1.1 +-34.92049351516548, 49.16474816565445, 1.1, 1.1 +-34.52800457209852, 49.101905634426494, 1.1, 1.1 +-34.135068122751534, 49.04146595336315, 1.1, 1.1 +-33.74165496982588, 48.983610273006576, 1.1, 1.1 +-33.347797811113765, 48.92838473622654, 1.1, 1.1 +-32.95355193850222, 48.87578600164281, 1.1, 1.1 +-32.55897272343497, 48.82581080743185, 1.1, 1.1 +-32.16411545779906, 48.778455732656745, 1.1, 1.1 +-31.76903559259488, 48.73371735638058, 1.1, 1.1 +-31.373788419709463, 48.691592496336526, 1.1, 1.1 +-30.978414910828903, 48.65206396828339, 1.1, 1.1 +-30.58290862186276, 48.615070593140416, 1.1, 1.1 +-30.187253641476644, 48.580541645026194, 1.1, 1.1 +-29.79143397877947, 48.54840671628598, 1.1, 1.1 +-29.395433642880164, 48.51859531970839, 1.1, 1.1 +-28.99923664288767, 48.49103688852534, 1.1, 1.1 +-28.602827147024243, 48.4656605377421, 1.1, 1.1 +-28.206202291249692, 48.442350273730874, 1.1, 1.1 +-27.80938363542213, 48.420905852348206, 1.1, 1.1 +-27.41239560343987, 48.401117721320034, 1.1, 1.1 +-27.0152623805312, 48.38277632837231, 1.1, 1.1 +-26.618008311037748, 48.36567204167427, 1.1, 1.1 +-26.220657580187815, 48.349595388508554, 1.1, 1.1 +-25.823234532323024, 48.33433673704441, 1.1, 1.1 +-25.425763432228337, 48.3196866941211, 1.1, 1.1 +-25.028268624245396, 48.30543562790791, 1.1, 1.1 +-24.63077429360249, 48.291373906574094, 1.1, 1.1 +-24.233304784641234, 48.277292136958934, 1.1, 1.1 +-23.83588428258996, 48.262980607675026, 1.1, 1.1 +-23.438537211346922, 48.248229925561624, 1.1, 1.1 +-23.041285846780326, 48.23284310829888, 1.1, 1.1 +-22.644128756870057, 48.21677695661386, 1.1, 1.1 +-22.247048916488293, 48.20009058111389, 1.1, 1.1 +-21.850028823167214, 48.18284476309637, 1.1, 1.1 +-21.453051133552318, 48.165100283858685, 1.1, 1.1 +-21.056098424732433, 48.14691816336831, 1.1, 1.1 +-20.659153273796377, 48.12835910336597, 1.1, 1.1 +-20.262198337389673, 48.109484044262445, 1.1, 1.1 +-19.86521611304447, 48.0903537673551, 1.1, 1.1 +-19.468189257406284, 48.07102913349803, 1.1, 1.1 +-19.07110034756391, 48.05157100354534, 1.1, 1.1 +-18.673931960606208, 48.03204031790777, 1.1, 1.1 +-18.276666753178674, 48.0124977783261, 1.1, 1.1 +-17.879287222813478, 47.993004325211054, 1.1, 1.1 +-17.4817967904475, 47.973691624854794, 1.1, 1.1 +-17.084270955362463, 47.954937094109326, 1.1, 1.1 +-16.686801128174533, 47.93717153235359, 1.1, 1.1 +-16.28947832171647, 47.920825898079805, 1.1, 1.1 +-15.892393867047751, 47.90633099066694, 1.1, 1.1 +-15.495638936114469, 47.89411760949385, 1.1, 1.1 +-15.099305337316125, 47.8845809125504, 1.1, 1.1 +-14.703556400500373, 47.8734776651785, 1.1, 1.1 +-14.308697305061001, 47.8473829972037, 1.1, 1.1 +-13.915049937292967, 47.79179229529915, 1.1, 1.1 +-13.526172469351751, 47.693253878691976, 1.1, 1.1 +-13.157065789084204, 47.542038841519194, 1.1, 1.1 +-12.825258618033496, 47.329240655236305, 1.1, 1.1 +-12.547624767218892, 47.04883107213538, 1.1, 1.1 +-12.336847240848291, 46.71319929363466, 1.1, 1.1 +-12.203957764845512, 46.341991680772765, 1.1, 1.1 +-12.159887187274183, 45.954831045813435, 1.1, 1.1 +-12.204178295940308, 45.56652407876719, 1.1, 1.1 +-12.314439388167633, 45.18260100257517, 1.1, 1.1 +-12.465784261829132, 44.80753656181107, 1.1, 1.1 +-12.637795253951083, 44.44460833224821, 1.1, 1.1 +-12.825248355222817, 44.09302305431002, 1.1, 1.1 +-13.026145738496929, 43.75112284650856, 1.1, 1.1 +-13.238489497069306, 43.417250145582564, 1.1, 1.1 +-13.460281724235868, 43.08974714960076, 1.1, 1.1 +-13.689524672405845, 42.766956136188554, 1.1, 1.1 +-13.924226560738893, 42.44722550883512, 1.1, 1.1 +-14.163135883227676, 42.12963909290556, 1.1, 1.1 +-14.406433551744325, 41.814703982627314, 1.1, 1.1 +-14.654464683132032, 41.50309020429199, 1.1, 1.1 +-14.907574076007238, 41.19546778419123, 1.1, 1.1 +-15.166106688099795, 40.89250682817335, 1.1, 1.1 +-15.430407636252843, 40.59487720341663, 1.1, 1.1 +-15.700821719082876, 40.303249015769374, 1.1, 1.1 +-15.977693894319703, 40.01829229152326, 1.1, 1.1 +-16.26136927880648, 39.74067705696989, 1.1, 1.1 +-16.552192591603035, 39.47107325884425, 1.1, 1.1 +-16.850509029109173, 39.21015108255132, 1.1, 1.1 +-17.15666331038474, 38.95858039526939, 1.1, 1.1 +-17.471000631829522, 38.71703130284675, 1.1, 1.1 +-17.79380922726624, 38.48611639165788, 1.1, 1.1 +-18.124662672932928, 38.26572308901189, 1.1, 1.1 +-18.46264455552472, 38.05524127479115, 1.1, 1.1 +-18.80682875582282, 37.85405136163408, 1.1, 1.1 +-19.15628923416506, 37.661533762179076, 1.1, 1.1 +-19.51009987133263, 37.47706857083787, 1.1, 1.1 +-19.867334548106665, 37.300036359362245, 1.1, 1.1 +-20.227190378553292, 37.12998230225834, 1.1, 1.1 +-20.58966505552905, 36.96752574821768, 1.1, 1.1 +-20.95507712394861, 36.81371612930074, 1.1, 1.1 +-21.323745924293434, 36.66960391180468, 1.1, 1.1 +-21.69599079704495, 36.53623964158336, 1.1, 1.1 +-22.072131003127918, 36.41467370537725, 1.1, 1.1 +-22.452485883023765, 36.30595664904024, 1.1, 1.1 +-22.837176044647265, 36.21059079339934, 1.1, 1.1 +-23.225608631678632, 36.12711126145291, 1.1, 1.1 +-23.617031038000658, 36.053612511793055, 1.1, 1.1 +-24.010690577939517, 35.98818876434185, 1.1, 1.1 +-24.40583456582134, 35.928934318578065, 1.1, 1.1 +-24.801710236415605, 35.87394347398046, 1.1, 1.1 +-25.197566892965256, 35.82132079283843, 1.1, 1.1 +-25.59291661440089, 35.77066451395842, 1.1, 1.1 +-25.987807771179074, 35.72461830555116, 1.1, 1.1 +-26.38235428845412, 35.68619672903233, 1.1, 1.1 +-26.77666985271035, 35.658414504930946, 1.1, 1.1 +-27.170868229988702, 35.644286115105984, 1.1, 1.1 +-27.565063345443498, 35.64682628008648, 1.1, 1.1 +-27.95936013432513, 35.668348348781024, 1.1, 1.1 +-28.353805375956718, 35.706442629151226, 1.1, 1.1 +-28.748421743989788, 35.756749495127785, 1.1, 1.1 +-29.143231832519202, 35.81490311522103, 1.1, 1.1 +-29.538258156083128, 35.87653781705458, 1.1, 1.1 +-29.933523308776415, 35.9372879282521, 1.1, 1.1 +-30.32904988469392, 35.99278769688053, 1.1, 1.1 +-30.72481918801771, 36.039967030967176, 1.1, 1.1 +-31.120659376336267, 36.08056241399191, 1.1, 1.1 +-31.516363443189015, 36.11742436151273, 1.1, 1.1 +-31.91172406388871, 36.15340346864429, 1.1, 1.1 +-32.30653415241811, 36.19135033050127, 1.1, 1.1 +-32.700586384089995, 36.23411554219831, 1.1, 1.1 +-33.09367446845383, 36.284541504512866, 1.1, 1.1 +-33.48571733726084, 36.3441243602187, 1.1, 1.1 +-33.87689789129997, 36.411528352792814, 1.1, 1.1 +-34.267432445162406, 36.485059482018166, 1.1, 1.1 +-34.65753723388267, 36.56302414546111, 1.1, 1.1 +-35.04742865160861, 36.643728342904595, 1.1, 1.1 +-35.43732285381808, 36.72547839235828, 1.1, 1.1 +-35.82743122258857, 36.80660654730689, 1.1, 1.1 +-36.21778995620587, 36.88636449769352, 1.1, 1.1 +-36.608217904127834, 36.965145492147926, 1.1, 1.1 +-36.99852039117802, 37.04341374385123, 1.1, 1.1 +-37.388502821736736, 37.121633545541314, 1.1, 1.1 +-37.77797036151423, 37.20026926951262, 1.1, 1.1 +-38.16672841489076, 37.27978520850301, 1.1, 1.1 +-38.55470951780849, 37.36036322906469, 1.1, 1.1 +-38.942335161515686, 37.44110044252706, 1.1, 1.1 +-39.330144342465196, 37.52083341211869, 1.1, 1.1 +-39.718675977553204, 37.5983985419548, 1.1, 1.1 +-40.1084689041192, 37.67263247482068, 1.1, 1.1 +-40.500062118616036, 37.742371614831534, 1.1, 1.1 +-40.8939921512397, 37.8064495020624, 1.1, 1.1 +-41.29034738945283, 37.86311692396588, 1.1, 1.1 +-41.68824244705264, 37.90935908045629, 1.1, 1.1 +-42.08666416982112, 37.94199481844678, 1.1, 1.1 +-42.48459948309696, 37.95784322352052, 1.1, 1.1 +-42.88103523266215, 37.9537232221473, 1.1, 1.1 +-43.27495834385537, 37.926453899910356, 1.1, 1.1 +-43.66535295753175, 37.872903110632734, 1.1, 1.1 +-44.05110376870643, 37.7917721712006, 1.1, 1.1 +-44.43096826127605, 37.6841028762339, 1.1, 1.1 +-44.803695804356614, 37.551089132709436, 1.1, 1.1 +-45.16803560795089, 37.39392532494402, 1.1, 1.1 +-45.522736961618214, 37.21380535991448, 1.1, 1.1 +-45.866549154918026, 37.01192354238096, 1.1, 1.1 +-46.19819029119424, 36.7894557995124, 1.1, 1.1 +-46.51591998869006, 36.54731313475993, 1.1, 1.1 +-46.817649009641926, 36.28620431851447, 1.1, 1.1 +-47.101279365052356, 36.0068333477666, 1.1, 1.1 +-47.36471314548054, 35.709904060393555, 1.1, 1.1 +-47.60585236192898, 35.39612029427257, 1.1, 1.1 +-47.82260228722377, 35.066187717084375, 1.1, 1.1 +-48.013520320231414, 34.72114072467836, 1.1, 1.1 +-48.17861059789884, 34.36274372492631, 1.1, 1.1 +-48.31807185279272, 33.99285921907655, 1.1, 1.1 +-48.43210249925305, 33.61334970837744, 1.1, 1.1 +-48.520901269846505, 33.22607753496397, 1.1, 1.1 +-48.58466665846973, 32.83290527964115, 1.1, 1.1 +-48.62359731813274, 32.43569536410067, 1.1, 1.1 +-48.63789174273217, 32.03631021003418, 1.1, 1.1 +-48.627748505721364, 31.63661231869003, 1.1, 1.1 +-48.59336626011031, 31.238464111759907, 1.1, 1.1 +-48.53494357935236, 30.84372809049214, 1.1, 1.1 +-48.45267903690081, 30.45426675613505, 1.1, 1.1 +-48.34677112665233, 30.071942450823684, 1.1, 1.1 +-48.21755183859921, 29.698490942027856, 1.1, 1.1 +-48.06737835737633, 29.33372200974479, 1.1, 1.1 +-47.90018285105427, 28.97594762050785, 1.1, 1.1 +-47.7199390162864, 28.623440360297785, 1.1, 1.1 +-47.530620549726144, 28.27447289465197, 1.1, 1.1 +-47.336200909356805, 27.92731780955114, 1.1, 1.1 +-47.14065387138847, 27.58024777053267, 1.1, 1.1 +-46.947542142706936, 27.231727174713512, 1.1, 1.1 +-46.75731871900259, 26.88167153290799, 1.1, 1.1 +-46.569013963557026, 26.530660495028354, 1.1, 1.1 +-46.381650761324664, 26.17927697281037, 1.1, 1.1 +-46.194252076816575, 25.828103957546517, 1.1, 1.1 +-46.00584095410053, 25.477724440529254, 1.1, 1.1 +-45.81544035768763, 25.128721413051046, 1.1, 1.1 +-45.62229752234734, 24.78153609641486, 1.1, 1.1 +-45.426588188768115, 24.43602290191088, 1.1, 1.1 +-45.228728438344554, 24.091884446699197, 1.1, 1.1 +-45.029134113801234, 23.74882334793981, 1.1, 1.1 +-44.82822121697609, 23.406542222792783, 1.1, 1.1 +-44.62640582926369, 23.0647437679748, 1.1, 1.1 +-44.42410379338864, 22.723130521089267, 1.1, 1.1 +-44.22173119074551, 22.381405178852873, 1.1, 1.1 +-44.01970394361557, 22.039270278868987, 1.1, 1.1 +-43.818437974280045, 21.696428517854322, 1.1, 1.1 +-43.618349364133564, 21.352582512968926, 1.1, 1.1 +-43.41985403545734, 21.00743480181616, 1.1, 1.1 +-43.223367990089315, 20.6606881606694, 1.1, 1.1 +-43.02927835079548, 20.312067005216825, 1.1, 1.1 +-42.836709437287034, 19.96225592062105, 1.1, 1.1 +-42.643058871266, 19.613252654472838, 1.1, 1.1 +-42.44559952957265, 19.267149547245936, 1.1, 1.1 +-42.24160412993393, 18.926038859857474, 1.1, 1.1 +-42.02834578786016, 18.592012932781188, 1.1, 1.1 +-41.80309722107828, 18.267164186047534, 1.1, 1.1 +-41.56321730719102, 17.953569685249267, 1.1, 1.1 +-41.30746520078509, 17.653058358719132, 1.1, 1.1 +-41.035740819567124, 17.367256901729647, 1.1, 1.1 +-40.74797701770593, 17.097786122359594, 1.1, 1.1 +-40.444106808483674, 16.84626690824445, 1.1, 1.1 +-40.1240630460692, 16.614320067462984, 1.1, 1.1 +-39.78778113044483, 16.403566248980646, 1.1, 1.1 +-39.43588430857907, 16.215547658884294, 1.1, 1.1 +-39.07063835449065, 16.05162018153492, 1.1, 1.1 +-38.69454890556442, 15.913112095128335, 1.1, 1.1 +-38.31012144007189, 15.801351836973724, 1.1, 1.1 +-37.91986159539789, 15.717667923936908, 1.1, 1.1 +-37.52627500892726, 15.663388634213717, 1.1, 1.1 +-37.13185013380371, 15.639806922837595, 1.1, 1.1 +-36.73830762172937, 15.64661347346778, 1.1, 1.1 +-36.34630405391834, 15.681279895511235, 1.1, 1.1 +-35.95641796648942, 15.741114707197314, 1.1, 1.1 +-35.569227975118125, 15.823426585868697, 1.1, 1.1 +-35.18531269547997, 15.925523970198082, 1.1, 1.1 +-34.8052505841371, 16.04471553752815, 1.1, 1.1 +-34.42973147699249, 16.178565660345416, 1.1, 1.1 +-34.06128599222599, 16.32887462658073, 1.1, 1.1 +-33.70395863192906, 16.50092579482203, 1.1, 1.1 +-33.36183876815619, 16.70010570866086, 1.1, 1.1 +-33.03841169915129, 16.93012425482624, 1.1, 1.1 +-32.734545706432655, 17.187427716336288, 1.1, 1.1 +-32.450400460241006, 17.46649589439051, 1.1, 1.1 +-32.18576513539551, 17.761980750826595, 1.1, 1.1 +-31.93744123545483, 18.069924182098912, 1.1, 1.1 +-31.700788219740822, 18.387038747406773, 1.1, 1.1 +-31.471156000774712, 18.71004146112319, 1.1, 1.1 +-31.243894809304415, 19.035649258064453, 1.1, 1.1 +-31.014354637407823, 19.360579232160223, 1.1, 1.1 +-30.777885556719504, 19.68154823867013, 1.1, 1.1 +-30.530448634115015, 19.995270587040313, 1.1, 1.1 +-30.270680268236188, 20.298448891886125, 1.1, 1.1 +-29.99794838132393, 20.58778234688601, 1.1, 1.1 +-29.711658207698296, 20.860054157564058, 1.1, 1.1 +-29.41296117107327, 21.116017089150795, 1.1, 1.1 +-29.105474474654955, 21.362028037966237, 1.1, 1.1 +-28.792998381551747, 21.604860220394986, 1.1, 1.1 +-28.47812986020796, 21.848820595989462, 1.1, 1.1 +-28.160516872349977, 22.092169101219522, 1.1, 1.1 +-27.8393636125877, 22.33225633979404, 1.1, 1.1 +-27.513874116417714, 22.566432517638464, 1.1, 1.1 +-27.18325257844993, 22.792048079348305, 1.1, 1.1 +-26.846703193294275, 23.006453469519066, 1.1, 1.1 +-26.503440497928032, 23.20702514777797, 1.1, 1.1 +-26.153188908039358, 23.39241661745134, 1.1, 1.1 +-25.79640364690548, 23.563112537785013, 1.1, 1.1 +-25.433596582154088, 23.719738701561, 1.1, 1.1 +-25.06527926318619, 23.862920981117973, 1.1, 1.1 +-24.69196355762947, 23.993285169237936, 1.1, 1.1 +-24.314161014884935, 24.111457138259563, 1.1, 1.1 +-23.932383502580258, 24.218062680964856, 1.1, 1.1 +-23.547142570116446, 24.313727669692508, 1.1, 1.1 +-23.158950085121223, 24.399077897224494, 1.1, 1.1 +-22.768317756108875, 24.47473931545618, 1.1, 1.1 +-22.375757132480445, 24.541337717169554, 1.1, 1.1 +-21.981780081863615, 24.59949889514663, 1.1, 1.1 +-21.586897994546042, 24.649848880839418, 1.1, 1.1 +-21.19150952901115, 24.693108139469622, 1.1, 1.1 +-20.79572853085656, 24.730234692481538, 1.1, 1.1 +-20.399624771283655, 24.762223634728613, 1.1, 1.1 +-20.003267862380426, 24.79007014062099, 1.1, 1.1 +-19.60672757534821, 24.814769305012113, 1.1, 1.1 +-19.210073601831713, 24.837316143198777, 1.1, 1.1 +-18.813374917465538, 24.858698828603973, 1.1, 1.1 +-18.416666845412067, 24.87953480055913, 1.1, 1.1 +-18.019934985913665, 24.89989685341916, 1.1, 1.1 +-17.623160961379103, 24.91981402536932, 1.1, 1.1 +-17.226326235103794, 24.93931543415157, 1.1, 1.1 +-16.829412588609866, 24.95843019750788, 1.1, 1.1 +-16.432401564749387, 24.977187274066832, 1.1, 1.1 +-16.03527582016789, 24.995600108906043, 1.1, 1.1 +-15.638037184668814, 25.01339192436355, 1.1, 1.1 +-15.240704672296767, 25.03003080453033, 1.1, 1.1 +-14.84329761532305, 25.044976002706782, 1.1, 1.1 +-14.445835505132294, 25.057686772193247, 1.1, 1.1 +-14.048337753552497, 25.067622366290127, 1.1, 1.1 +-13.650823851968276, 25.07424203829776, 1.1, 1.1 +-13.253311780187499, 25.07709454277256, 1.1, 1.1 +-12.85580670939388, 25.07652070049737, 1.1, 1.1 +-12.458307287123958, 25.073274867836183, 1.1, 1.1 +-12.06081192224431, 25.068115299429873, 1.1, 1.1 +-11.66331910317817, 25.061799931692658, 1.1, 1.1 +-11.265827318348768, 25.055086939708744, 1.1, 1.1 +-10.868335056179323, 25.04873433944904, 1.1, 1.1 +-10.470841043763102, 25.043389165326943, 1.1, 1.1 +-10.073345281100103, 25.03916741097025, 1.1, 1.1 +-9.675848086417, 25.036026911342784, 1.1, 1.1 +-9.278349937053838, 25.0339252627384, 1.1, 1.1 +-8.880850992123944, 25.03282006145089, 1.1, 1.1 +-8.483351808524045, 25.03266914244408, 1.1, 1.1 +-8.085852545367478, 25.03343010201183, 1.1, 1.1 +-7.688353679994251, 25.035060536447922, 1.1, 1.1 +-7.290855530631089, 25.037518201159553, 1.1, 1.1 +-6.89335849506133, 25.040760692440518, 1.1, 1.1 +-6.49586281195501, 25.044745845254667, 1.1, 1.1 +-6.0983689586521175, 25.049431096782467, 1.1, 1.1 +-5.700877253379394, 25.05477428198777, 1.1, 1.1 +-5.3033880143634855, 25.060733076721053, 1.1, 1.1 +-4.905901639387784, 25.06726499771947, 1.1, 1.1 +-4.508418367122284, 25.07432787994686, 1.1, 1.1 +-4.110938754463695, 25.08187931969704, 1.1, 1.1 +-3.713462960525359, 25.08987707237718, 1.1, 1.1 +-3.3159914626473204, 25.098278654724425, 1.1, 1.1 +-2.9185244994995734, 25.10704182214593, 1.1, 1.1 +-2.5210625484221754, 25.11612425049221, 1.1, 1.1 +-2.1236059276417993, 25.12548361561373, 1.1, 1.1 +-1.7261549553851319, 25.135077513804333, 1.1, 1.1 +-1.328709949878873, 25.144863700471184, 1.1, 1.1 +-0.9312713884630399, 25.15479985146476, 1.1, 1.1 +-0.5338395098076538, 25.164843563078886, 1.1, 1.1 +-0.1364147116960799, 25.17495259072073, 1.1, 1.1 +0.2610029263150168, 25.185092247681293, 1.1, 1.1 +0.6584142793490314, 25.19524908888302, 1.1, 1.1 +1.0558202225293325, 25.20541332885523, 1.1, 1.1 +1.4532217105360197, 25.215575182127292, 1.1, 1.1 +1.8506196184924484, 25.225724863228525, 1.1, 1.1 +2.248015060192062, 25.235852427574958, 1.1, 1.1 +2.6454088312015505, 25.24594824880925, 1.1, 1.1 +3.0428018862010004, 25.256002461904078, 1.1, 1.1 +3.4401951798704586, 25.26600520183213, 1.1, 1.1 +3.837589666889999, 25.275946762679403, 1.1, 1.1 +4.2349863019396805, 25.28581727941856, 1.1, 1.1 +4.6323859601429, 25.295606966578976, 1.1, 1.1 +5.029789675736394, 25.305305959133303, 1.1, 1.1 +5.427198244286894, 25.31490455116755, 1.1, 1.1 +5.824612779587775, 25.324392957211074, 1.1, 1.1 +6.222034077205782, 25.333761232679866, 1.1, 1.1 +6.6194630918209745, 25.342999751216617, 1.1, 1.1 +7.016900857670091, 25.352098568237327, 1.1, 1.1 +7.414348249876513, 25.361047898271334, 1.1, 1.1 +7.811806223120314, 25.369838035404662, 1.1, 1.1 +8.209275732081554, 25.378459035053282, 1.1, 1.1 +8.60675765188363, 25.38690127085993, 1.1, 1.1 +9.004252937206612, 25.39515479824057, 1.1, 1.1 +9.401762542730534, 25.403209831724553, 1.1, 1.1 +9.799287502692177, 25.41105658584122, 1.1, 1.1 +10.196828612658216, 25.41868527511992, 1.1, 1.1 +10.594386906865415, 25.42608611408999, 1.1, 1.1 +10.99196158974706, 25.433317656462037, 1.1, 1.1 +11.389543750955868, 25.440798688557486, 1.1, 1.1 +11.787121456991036, 25.44906645658243, 1.1, 1.1 +12.184682774351772, 25.45865820674289, 1.1, 1.1 +12.582216008207295, 25.470111185244924, 1.1, 1.1 +12.979709145500124, 25.48396255873796, 1.1, 1.1 +13.377150332286128, 25.500748618747963, 1.1, 1.1 +13.774492868798859, 25.5199576567606, 1.1, 1.1 +14.17158766583495, 25.538003178445127, 1.1, 1.1 +14.568267017929822, 25.550737974046548, 1.1, 1.1 +14.96436337873224, 25.554014674696475, 1.1, 1.1 +15.359708883664258, 25.543686150196574, 1.1, 1.1 +15.754135986374623, 25.515605190791796, 1.1, 1.1 +16.147465604794665, 25.465642168751636, 1.1, 1.1 +16.538643851690306, 25.3910312963738, 1.1, 1.1 +16.92513605149143, 25.291315361464253, 1.1, 1.1 +17.30426424706161, 25.166260467407326, 1.1, 1.1 +17.673350401707786, 25.01563271758728, 1.1, 1.1 +18.029716558293533, 24.83919813583176, 1.1, 1.1 +18.370684759682437, 24.636722825525077, 1.1, 1.1 +18.693610144313663, 24.40802253341485, 1.1, 1.1 +18.996615652067867, 24.154067930456236, 1.1, 1.1 +19.278597275007634, 23.876992408365776, 1.1, 1.1 +19.538485135007814, 23.57898035468672, 1.1, 1.1 +19.775209115273256, 23.262216077405693, 1.1, 1.1 +19.987699178565457, 22.928884202735993, 1.1, 1.1 +20.174886401439355, 22.58116895910757, 1.1, 1.1 +20.336965379514663, 22.2212700089447, 1.1, 1.1 +20.477881487269524, 21.851431884634724, 1.1, 1.1 +20.60227295823861, 21.47390747201552, 1.1, 1.1 +20.714778025956548, 21.090949577368285, 1.1, 1.1 +20.820034764844646, 20.704811166087577, 1.1, 1.1 +20.922681408437562, 20.317745124011275, 1.1, 1.1 +21.02733120947492, 19.931991767023085, 1.1, 1.1 +21.13661980094363, 19.54880681763394, 1.1, 1.1 +21.249801418600324, 19.167762022278445, 1.1, 1.1 +21.365799103776016, 18.78826404729677, 1.1, 1.1 +21.483535738688413, 18.409719797699115, 1.1, 1.1 +21.601934364668605, 18.03153593982565, 1.1, 1.1 +21.719917943490913, 17.653119299129887, 1.1, 1.1 +21.836436724868257, 17.27389181683304, 1.1, 1.1 +21.951087197360188, 16.89363813302398, 1.1, 1.1 +22.064124737883876, 16.51251250808972, 1.1, 1.1 +22.17583431843841, 16.130685670648408, 1.1, 1.1 +22.28650099057963, 15.748328349318152, 1.1, 1.1 +22.396409726306633, 15.365611431830425, 1.1, 1.1 +22.50584557717523, 14.982705805916698, 1.1, 1.1 +22.615093435627884, 14.599782041081763, 1.1, 1.1 +22.72443843277706, 14.217011184170415, 1.1, 1.1 +22.834165540621868, 13.834563884244119, 1.1, 1.1 +22.944559731161455, 13.452610949477673, 1.1, 1.1 +23.05590597639495, 13.071323188045872, 1.1, 1.1 +23.168489327878135, 12.690871487680187, 1.1, 1.1 +23.282594757610152, 12.311426576998748, 1.1, 1.1 +23.39827851215812, 11.93289083996499, 1.1, 1.1 +23.51429910965535, 11.553645298303595, 1.1, 1.1 +23.62895841293788, 11.17153500043992, 1.1, 1.1 +23.74044070008051, 10.784438726828254, 1.1, 1.1 +23.83643879259383, 10.393304156545542, 1.1, 1.1 +23.88599488225668, 10.004534090111537, 1.1, 1.1 +23.856236947762675, 9.625092839037, 1.1, 1.1 +23.727006044435438, 9.261564593053874, 1.1, 1.1 +23.51756785463807, 8.919353875561573, 1.1, 1.1 +23.254807760108452, 8.603637439207546, 1.1, 1.1 +22.965133166099005, 8.319300779663044, 1.1, 1.1 +22.663248532296688, 8.064096739170573, 1.1, 1.1 +22.35174478083874, 7.828395300810435, 1.1, 1.1 +22.03264758370781, 7.602266280339459, 1.1, 1.1 +21.70752436645573, 7.379343871090376, 1.1, 1.1 +21.377136088650275, 7.159537617127115, 1.1, 1.1 +21.042161448260316, 6.9433953456931095, 1.1, 1.1 +20.703279222811418, 6.73146480447513, 1.1, 1.1 +20.361168189829133, 6.524293741159933, 1.1, 1.1 +20.016507206395694, 6.322429903434288, 1.1, 1.1 +19.66996255963917, 6.126389773212864, 1.1, 1.1 +19.32189153857352, 5.935905483181008, 1.1, 1.1 +18.97232779567102, 5.749887902498954, 1.1, 1.1 +18.621289469852876, 5.567208997114328, 1.1, 1.1 +18.268794779596973, 5.38674081253141, 1.1, 1.1 +17.914861943381222, 5.207355394254509, 1.1, 1.1 +17.559509179683495, 5.027925424241279, 1.1, 1.1 +17.202464166015524, 4.8488448671315005, 1.1, 1.1 +16.842536098110703, 4.675321582231392, 1.1, 1.1 +16.478352782490273, 4.513513335510922, 1.1, 1.1 +16.10859691977916, 4.369358873422027, 1.1, 1.1 +15.73336111394356, 4.243160988658367, 1.1, 1.1 +15.3542368166503, 4.129230504048091, 1.1, 1.1 +14.97288294362406, 4.021608306631224, 1.1, 1.1 +14.59046261340958, 3.916207649723459, 1.1, 1.1 +14.207242181744725, 3.8123295484045623, 1.1, 1.1 +13.823393809267717, 3.7096313520881896, 1.1, 1.1 +13.43908941794679, 3.6077706488580237, 1.1, 1.1 +13.054501088863443, 3.5064048676844166, 1.1, 1.1 +12.669800903099274, 3.405191517094374, 1.1, 1.1 +12.285157679912261, 3.303794549705338, 1.1, 1.1 +11.900655033364673, 3.2020499992163067, 1.1, 1.1 +11.516285087345995, 3.0999789481453592, 1.1, 1.1 +11.132035271902048, 2.9976114689145144, 1.1, 1.1 +10.747893335305342, 2.894977872615813, 1.1, 1.1 +10.363846628045033, 2.7921082316712664, 1.1, 1.1 +9.979882739280276, 2.6890327776162373, 1.1, 1.1 +9.595989337726927, 2.5857816624294165, 1.1, 1.1 +9.212153773874117, 2.4823851176461718, 1.1, 1.1 +8.828363716437691, 2.3788732952451874, 1.1, 1.1 +8.444606754576826, 2.2752763472051605, 1.1, 1.1 +8.060870238780668, 2.1716245846181117, 1.1, 1.1 +7.677141917321726, 2.0679480003494075, 1.1, 1.1 +7.293409140689157, 1.9642769054910625, 1.1, 1.1 +6.909661089175546, 1.8606380310848842, 1.1, 1.1 +6.525895216967414, 1.757037423437947, 1.1, 1.1 +6.142112478744822, 1.6534733323034543, 1.1, 1.1 +5.758313670074484, 1.549944007434629, 1.1, 1.1 +5.374499825193141, 1.446447778141359, 1.1, 1.1 +4.990671580554151, 1.3429828146201896, 1.1, 1.1 +4.6068299703942674, 1.239547525737674, 1.1, 1.1 +4.2229757902802065, 1.136140002133692, 1.1, 1.1 +3.839109915335376, 1.032758652674797, 1.1, 1.1 +3.45523330023981, 0.9294016475575401, 1.1, 1.1 +3.0713466610035733, 0.8260673160918032, 1.1, 1.1 +2.687451031863404, 0.7227539080308026, 1.1, 1.1 +2.3035471288293414, 0.6194596731277552, 1.1, 1.1 +1.9196359065814446, 0.5161828611358773, 1.1, 1.1 +1.5357181606864574, 0.41292180136506373, 1.1, 1.1 +1.1517948458244265, 0.3096747435685179, 1.1, 1.1 +0.7678668371187467, 0.2064398579427846, 1.1, 1.1 +0.3839349301361352, 0.10321555335443694, 1.1, 1.1 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_map.png b/gym/f110_gym/maps/Spielberg/Spielberg_map.png new file mode 100644 index 0000000000000000000000000000000000000000..e9ef68d14b471ae811438323162d4d825244a18c GIT binary patch literal 62176 zcmeFZg)L#h<9u_8}K^rrJ3e`ZMl@5a&$lB@J_SDyn@eEUKz7I%~C*A}MuSME0K`k=xO8whB zO6}}7#^-)o_`E=)9s+)*fbz^c00i=6a)H+jxY0}>Z5$#~tO^S7?>ETF zby+>kUG0rWZjXE{{2fInP}fvC3DHXDruF0`A)hWoDgG&)`wJ-%qwqH^x3g$Hylp|5NZlL&gbQzOzY*iQh%I z7t=8m*wqq6t^R%`z|ijT?X5GS(MwDcaociG*xK6sPbtI#aaf`7bO(Ru=H{-dsm;0t zFvWVSC2L!5>UviRR||?%3jz-gPB)PzWNhjQ&z$7V01nF9ZSbeNc-~U6p75FV$gfw8 zp9-3{X6EKb?#swrgCVcBnAc{7l@_}$J_uskM}gxo`_rozbz#+cG6BGEH|Xe_L@xZW=tXfSRohO_Wl$A}JOBL^9?KSm zB)u&d80SjVDSlH`p>-9REW{;j;|xfZ(_)}#Gium;*(-b#8S#nl>dUhXSwk*LZoP&N zPC8;j0;c7rof9}9Vo?{0ync`QThHiJEiuzyT_lY!q91GN@?6{0#pkT`t2pSWUmPni zOA9cAWNZ4M!NQ9tpF6$BY_v^B623lp5%q|#D>(kUgX*BlppB;b#h3y!9~V$HrVna+ zUAA{qsM5&RbkXpZjaE~Fs!xTL%FQP2XTgDjsZI$%s8Q%A$B*!>Q@NU2QD7#aVFAfL>Vv9M zrq!y7Ulxi$@%%DxHq7}i#^_gR;YuujgMcyhMuC}K24_mvsTK{Hj&q{&VhdIR)mK%O ze~}$zpo7Q-TqvSnYB)^x)wAI!rn{K%BMgQzl5xXk(w~P{1S+z=f9;d9k1%p6-y#|UVlfB6lk#g4Szre zN=GIXJvzUr=DNMIW@3?2>o(`F)Dp`gZKMW#Ncvr=spF9%b#fwOaGs?iKU{SeGSKD8 z{PmFyI*8T?1xBaI+Zjq(!^t>=cN@*Z1tdu{SbisgK%tSf5iJr9BeVYC;C@|pA3Ny4 z51^Uo2qs9Bwr~9GJHxzGja3Z<-B*ntp=_@+5CeRg0AT~QFugBrI$PM=n9;yxZJ%WI zvC|w_dc&M5S_o+Nd8dINkI%2Du1~GD`aXAS1y3)SdT&ZI=8UzX!|Ac!dNDc{xuJ6^5DBPqJZ83}Rm z`@6or-ly(=ZdL(ApE;WVqTBo`ZdxXLtu}SdJ9W!T=cEBot9e*h2BFHmIRQ9^SH5PN97y0cZR@zJyzpZD>YDW4lwa9(lEG#VC zENm<+dJq>M9}oYZg6K8m@u)S}b@oz^zI&d#hDf#aPTdfbqQmamU8pS5huL^OH#0K> z?qx=JepE=exwTxVbCl{YvhY9XpzB3I%mufgTak?CS(Z14tG!7&CG*)-H2luUjGzaE z)S`|@MB{C%?ZZ&dmu<;_I%+F1AB zOC-}EC)>t}ACVaUTHTB}RcQ<#w0{N+Ny>4)JHePrj?4IAqmKKAmj!{@eTW01l}YaY ziLFs{>ExxGO}Tg3&#ypm`}b<^(Wb6Td&L^NA-wuU9dP6)fOk;w>oQ23$n88ThP`#~ z0Aefnv-y4rd3 zZ@7Z*7r?S~atA+3_w}AERMmFKN0^|J@00p@2i_fvh3)O^Y zCVzhwJW(^*vQlQ#Dxm9mOds88M%If7n(75KW@bG6oW1CsVSkZsi9xONc%nVsyZzU( zY--7Z1p{Lm7pJK2sP8}l9_$-iepqScsinL{{$Lqi4T)|T53P=LiBO*t>IsfA2NjM`PZHl`=;!{|?^{s_0ywXwm7{s^_FT0_2W z{0Mb>9rcqw07?}ON|ynkd=4=I-|ZRnDINX%Q0%bl;3d7+N=^Pgkz29eaE0yg-;)`n z`+Hj*TW@$Eibiuo+q%RV92MUAS0D>Lz`w`9&vuzae8+#)a>92_^)~qaa*4#{+B$c?vWuAO^(=0?i}_MlGd_8vIat z<9&WP`=pzm;s{mg@q*+m(gOwGur?HzR--Ui-uw4Y>C=o@K^#zEqAiLV3y%gnNI5hb zw)=}fJ;U9kQ(eK<^ zv+iS{34Z==u+5xbsM%2LB^zn@xg(ani#S}FS66*H4rpZ)21>6;C>r$JPr95~?O7}( zLv19mhvJ2HrFL|iJNxU1EiZ>FmWSvFC8)P2q**--f z?b()Z0cyUZGq4UYADK4ts#N%fHn{Sw*tmdc*;JVjdH^w^2xsolJ;fi1cQ_gAzEM$M z6x^O~=>w)`SRq2%j3b)! z$qCC-DekGmbFnO73Nih{>6oOo;p&YzO(NbB(gP6_x=;k&-G=ehz6$X=toSl;^EPA% z+t=dfr2Fa@fOUmC<+ki3rm5#qxpU_6(0}e=O8_xqqQDR8JGYD9@XLjG9Ur?J?k_uM zM4uO$gAsFu$$t(2;v>EX%}z?zOD<}hq?|Xp6{iJ6R6r5hAV^#vly=uU_JPbi(CXs5y`ire z0)px52S%t0b6G+FGDHi_9kNqD(?j(XL;8r6h*${ zcbGoEr$G>PyQd@?s+_v(?z~DlqxfeWmfDh(pVa_QBqwsA2;b?n9de5=fOsS?mf*wQ z@Q}x%01l{^m%Lu=$?W7BB0pKi0aqV%&>CoYd+=s^9SuDo6JT%$Emjc&Y5DT=C*OG* zcTmn5Qx(~o-7D0qV|_rh90gOV;98b_34G-Pm>|DC1I6W^ds{V~z0iE) z)X5xt`%>bF;qTh~aD#&6!pGqX*9mBNDM*!^(T&O(hm|izqd+#~*J+?=cGd^4Lydx` zkOQ+>M=(t$@*+EcH%(_Jqjml!3pXnwZ{R-CJff5wElED?7VwVbLz6XrrhDM&T(y-d zQuyvHb++KhzJNSpI?5I3tS~vkjP&5w7iuh|*+HNY_l(2-m&c=d8Z=BG(Y`*YLX%_8 zgIljcJoiPh6z|bNaENKOjS(t&~hp~!{(OfkKPLQZA z(Da(SdFVClac1BRYMU_S<_Jw5M{h0XTX%=lOrEVZz?z^%`#W!|(kJz#EPowajpl05 zSfB?yA2jI5-WkVtooQSJPX$@JuNTigz{%+9)5!gXUtbxm_KM|inH(5xHchYM!=KFe zQkLfxR-<`pR?pB{GR#Xee;!)Q9(VKRI})W#mkQV;N#(!Y8;taPPI5P3(!vTk@3#Ji ze5T}{%U@H7PUQFMS?LCnlF(1J5xrT+t% zXYk-1prJv!UoE20$kyBlvCZwIWI6jJbGyT`5x zSHIk60wiDp2})jr2J?*wd#O%pHffuD&{B?RDf4ptwbFBc5yKFlYl6oq-X4|2g;JjZ z>$xs={tXPLXNt1IS`VvA{8Ph`OpJ#qK*k(=u>AWWG3dGoNa(~D&ts_Xp1lb1IXtlw zUyT=%@2X3E#iq6K#hDri1Ev+qzXx(u;su4c7Yi|_NR~Sz8ASZ&rl`?cTKRQ{r={2n zteR;G+ip%Pgj24IsF_^nRW!TJ>!4yM03REE2d0xqO0Ar5ORsY>`z?4Xo~a3fFuG8r zsUhu0oQTHr9h+q;p~yyd=D5IAi*9ZHN|k@6C*R_NIM-rpy;|#&!ttbIbe+YTNs_FW zM1p9tMnJ-vXw>-1@+MP0NBOfQqPn)tRzr5S_PKgaRPh* z#>>LyF5B5UyRE8{*(&?lI=9Y&FSm%znVFdnESh8m;lK)k(APvIwQM#`vT$t#C=Szw zqJ+Wlsoy0vUGVX%+2bDU2l%W=J2`QLm}mJi-Ew2m!qPgk0);hV?t7TrTw0~r5- z_zzxo?g%C$EedQTQ=@%32N%aVGOma6!W_efcwL{W=4l?4_dI?a-T9YH^=3NN(5}R% zvT}EHVx~wfgfsdc?_MN8zJIWR*LH$>`b;22U6-d^8vu3DT#bxlT|tV z!LC9Wcq5FqE`b8SH*S=_JiT%yPL*~lCnX}HxP+&|3xLQ*hIky^kw-*)i`ccjhvT0H z;QsHY+?N;N&j8@?%!i$inHZ`dLTnd`%0WN9%iDTaV#?H-S7k3h;od|cHBR)9$vtMv zW#?bQ93j3M|3Ulb2~jlxTtLy$H3C}`k(c=CWUGRVOi^I_wAwI2kY-{TSsO%H7uk37(RaGHt=_owNG0dPHNuP#RwR0Q6f|SXfu6 z>js5F-JnPy8{KSe4+Z9eDPW=>K%OTa-*{{=K1Gzj7NDnNN;fkB!}VgI1Nrx0Bf-*u zEOi=yBnB5nkA!{C_lJR`CK2-FK2sS!iuQxn-D=VW=eP)e_?`6xb9=m!<(?{YSt{LA zWge=CFw6gl(wL=kSN;3d=rV7b4qG~dfbPLjG)%E>m!B@!qFiKs>g7wkDWs)h;iS&0 z!u#K*WoCuJnG^HV3&X?1!2Q2ZO@6ZzcKX#-8(vS|4`c^SGF_@w7nah!MPn~Wr(2QC0ASha^H(Xi{5JMw9Dzd6g~x6n0YDjIeRmU z-uZR7pSww zHq2vo6kafF6Mv+7F)wIH(6S`Azl3ZbwyF0`J!ez`t|jnEvmorUOuD7IwnKm zg&Mn+97htZGZrV8>%APL<7R{bd7ajV;(X6zy3ZYdm(_5B?l!bsaz5UejvV0^S zIVAT+$_LIS;~pFkv|Kd0;c6XpN+XgrnT?l`Aaz>03Uu+9J$(hi^=#6B)$f2z9H(fl zc|d12Kx&JdGsjoqRO;uhUKwWQ9#WJwkgCn51wE)X!GM! z9na+6fTI$H{br7{3WNU+``;q9{T9Q~l@n{xk57nHbd7Alb2HOif~#f2=tjy-CUVG} zlo{l8{ykAkGhihT84$Ts7CIZGg!J@LWIFgmE`L#}hUg3U6Yq)WNsESlEoF!jcIbJb?t};8u_(ZtNGZ*1w7BP=>XbLaqkYf zyii3*0{ko-D!;fPdNvs$eGNv-=`}E^+m#v#ZMFu_^-S9c-jsbsC(PJ|15Na5Y77TC zX=J>5UX!s$(J&r|M7iuv?#rlBLVos9K^!d{&`PLX4d1=f14T{Im(Io`0 zdg)h*_^wDLdc;`j_j_J;I@3_A2Gcb^|Iv#5h*ap$-Errn=gv=WG}bPIjH_`kAJZL_8EKbB7}iI&u;Lh9u=W;Q zB-|Fb;b4Q!N(sTMrm%n*^J=^QWnuGGZu)t*;XMFdFamhf|HH#VF0<5P-Q$tg2_2}j3&1;@jP=;e_OZr{!*f`ybmOoRp_wuJthC79FeKocS*hm!5MoDs`4mjCJD9gU!r5F1II-kxl>|Vqegd59f7sFe zyW%27jLd&I7WMzlx6JT5#XPn?PU3Qip}@G&$zR85_8z6T-5kW}+^0YR{@oJ)L)fOP zZ10KNJu>h#3m5qh%d)Ge64t9Xt}J*o?-#{$U3M?p$g{KK;swu65XJ6UUe)G_2Nbsj z|Jc0zU+(uG2!VT+1r+<$oMK_UtA=}aM6qc`cOsF={TeOjw*l+lG7)pP-@Ffi^hTmm z?LH3#c^yRExA~{x|NY>;np0N=2m-*^A+1OM9F@|zZs}viQM-XDH0WdiaeSMqzOI?4a53j9%44$O8+B)8IVM#xXl9J<6zR# zZDI$GzOT7uJ6}|CB5P;Yqv8hGOra%IR|;A8et*fCt~m9;rdK429N5c*iqlIq8d}Z^ z%Z4OfeR5B^D#t?;rS;}78MLzLpPny4pGwbozQukb{!=sL@;v^e{WE6VBNuqg{dU`Q zHMGz%x}nUF>bk}NbQ$4M1^iUf=a*CpWx<%8=aR+3@hJWhA%|<5iSN5oruQFa{3t7?r)0m9UW*wUR!(CUF&ERQ! zO&TJG%=gQZW0I~fLI)ZvHACtzOef)KWC2UZ26qQKYMz;|y=vD~4gKH&Bc`R_j+PK~ z;%5`e6uX~1UQPPyf!fMZD>;c$lX1~re2vR5{*iF)W4XBNy^qg%EVBD;n4uG=o*<2~ z?rPs$Oo_|qNpjrxh$(gNdi9k+y1N&xWPFzn3SMi~a{HC&yxN*IT>$8x(gmK0J+M8N z>|kk7)(wHlX$69s{3?ilRQvZQAx6ba75-18O=NAW270D`xT!pCA1oDJQmjOJiiTPUcEL|2ZeRUY$O zbKSg7)6Rc)JA9`zUE)9z(Bf%_TJPxT?2s90v-+pfIC5}0tNJ$E0PE-s_HwmZR3Fqf z0v(S%H(p)dss6C>`kz`8_qBkfveLj41NR{Cp12_>@TYt6K%M@D=Q47fUs?7QpYBH8 znVOF)uucemGsr4p)6$rSBdg?pHQT5>VCB~ee{a&V)-7WZp&Do6o};;m~53a@=pG@Q=t+=!B(xKLXKTl;q#&ruEB{VLLg(Uf2gCZ6RaivQO47^@t zk5Q5UK;uNdYtF#_ZGq#gk%Wd>8ZA4hV;9iVTB){?JHd{a`^NxMv(noo8isF8=eQL1 zz1tz;hutsGIP8;tTRyS*#KjA2wE*H8ZP5*u1`!Y*jF3G9-jhwV_;mpdzF9gY|_v({BA-($%f zTxi^9C3w}SV5syovQRw9Qc0DFAEuK*6!gPSFi^6{OV2d2)8U`XS zG9;^>`pelf$bP4C=Ta7+2?*aNbK|w~$)nJ*SA8l!UPe+06fp*!Tra5xYji%XKmo=V zS$j!vw-RqIVp!b9o!a;c>6NYniWteowWAnR)%Mp>AL6>>NMA`Py4&Y!VynN9r`RnJ z(-#5)F^D|t45q(#6Lol8LbQH#$9Z3i;eg0b%R;7BHbf<@<~jSK7B{HFay3rsYp(aI z)hU^tWAS}}x&6g^SK4Fm_ZjajKGuDUz=MD|AoFMg-5m?Kj7m&&rhQ6u^LIN<&O z+6eqjI?Y0Xqy@FRHj;tuK6s~Xcy&f=drfYD=bq$wtnbKxsRB$7=g&9~)|^*2LgUvL zVJzvGh@$3=rgL^`$H6V_n#JVt0u_4>vVgy37KiRPf1o{+y?2E&jqg4YB-mh|9@b@bt0!YnEZ}a}+VHCSjNA)Lwr+~=A+27kN zeH-qXgw5seHLJ*S^6ScsdF?h*pYL;N*XS?qUQWS)AP{njP&wH-<23GHmUv*FPXUSO z8)tA!J_&drlL-0a?^<@eVS|~@;fvC1JoH%Yne1%JjP_TQeFcaXC*@cAsXwKl?Pf`H z!$lWQmgLQ&SuKS4i;EfIQn!}EVRYqhwU>GKe)ct5L+cNa1subp@nqAsq<1wg$0~bf zg>*N5Zeaps^+c;)<05u5Eupy0ZzpR+WRVx-w*zdGuUw4x=x){6t@Z*DGqG>nct@18 z;1fH0zN2xCCa|1l^7~nvCZ$E;Mpy@D$`{ zHCXiRvP&0UeTqv{>6jQmYEgP?bF{6Pc&-qHhf2Htw$1K979j1~4^2!g)LCdcU`lbx z3(&ME^)J2%&PhDDq`Q8GYC_o*K+H z8xOU2mD;l>ssg%H(l-q+y-q$n+Zfyk)W?hiwxw)}qK&fxsU(j3l1dx8F5(3hk&_(_H~;(--ym9MvpS z7`WrrJ0Br^PK_oySBJV*cet(Pgsm;+7L`&$+WN-#`qRn{k&V?au(o_hkwW`_ba7ft z-20)_A`W4PXS2&fKdsUONZ<3YXw2nk!QSQsR;FFVJQ$3`Z!tN!TK4Hl^^H87Oi4g) z@lpWEBG%2uicX5t%N)G#e(h$|r&ABnM8CNA8Dte9HPM>Rj5_W#dD7z$_#+M){p)jS z(EN9HdAI6M7}D5)Gc#$h`Y4}b`HNY8uX_JGYc$q=gLR=Zf}OghPGGB{RO`0*lAR5| z<;};9?FB?jSi);u?6HuJ?%IqRyzF_26({Oql6KE&&S34@ zKl;n5tlDA;&>hz=W*x@MU=jJC#mj)GR2f;>Z~-c3|I<@?!vj{W)X5zbtf)|8>-D;#CRJpfAHKTS)$<1!B=$0FjnLFg4sbWwCl*Te>_6c z<&PK;v+7Q@z;lVqx;Cge6Ld!Prx5*TmPzW@Zjm5b>LgQ|}}-FzbZMAj`Hpu6=t1%!`aH>uI#ngTekzRQc6SHo}*E!+~LVZ?03s5+up3 zyX;jQ?>ra}N#p}>8Lk4vp7B@_o#-r@$u%Pd88gw{23$#_{g~2!uUJCtVULL~aG2!o zjCY^o|EbQT7}Ix05(MR1$tqxV&DaYhmI%m4N~t}4Gl8YhB(F5o{6lJ=3|&_!$XjMU z?K68G4)N<&FJ~|q!6hGAoPhD@fF#WKQ%pL{Y@_yJtBq;;LYp+!eVn>9^LY3i@lYh8)d-$N<>0>%uwn!6LCnBnXxd&{?Wr2 zs1>lS^S;8cAc*?ZoyKud9*voSnPt7%V1qbRnT9!IA^T4Y_7gdU3zX-+gmxqs26VxX zAOn|GZbc;+^CnNl&f|%z88rXwmgC)s0AuF0_l_Z^Z2=Lqs6p{GqWg$7oR50TAS%!@#mlmnI0!J9N-`Nqjbv?gj0b5HaM zo!zlnU zSxOm~UGV|BomiOI_)z|fp>S3Dn(q30XJDANkK5BPMf&n7hW$_9OyMg?D=7`_?AUrd zrlXvwWAGZdwk|apc(>t_GWmG zi$J@6!iffK{{@qTv!d}vNRnR#!!0VIbg7X_b|otqle3~C^xjX>XW;G!IP-5P6tb0k z>$z$yztV4-FO(6Tag#G1z6ON5Jn)zJj| z6eIBkm`N_e?<^f-(2p^FrgkEfxG_UAY`u!`mytq|1sY@{mIUWZ5gKzED~nRC*bR%3 zzpiYhR>`;59)?!L!*(pcQx(hMau6%6Sp#1fLzr)T3?oGoE#?=0vQ0V%c*F}Em4Gn& zjd!!<&q_E6;p!sdp|8ngSK5Oy3l63s@8(n>drCzDHD*xauyxAQs``M-=I?>Z6TPxvv_oXpl%HozW^RA-akD3|@#)7ZJY~W14rBrAFs)>^sq323s zosiBL$ai*h$ST}1HMO$}8ooxiR`Y-GJ5o({WfbUC@V(%E2V=gaef&qCCXs-!+wokV z()5eNclni7v2=@)=*)|3EJ~~wo1$UJE4juJI)P!ER6>Pg-tVV9az(6i5Uzp^)-Q=5 zW(IZ^CGLxBg%3?T1Sb=2{jE>Rf%)xjZT7Zy{n`&SRyVTExT{x;^);G|G&|AvJzfRA zk8C5we2J%TB8cRsJI96EI()1T@8hmpeStTvg0$WXi z>;+K;yuFcC5J}mtqxvn@m~JHhS+(JiCk%&}bcJ@yPldRmj&sas$M8dQGnK+|eagIg z#_?c(#==G}yVIR7!9Vq~lXr_C*OM zNE~Ob!7R3a!0g;`z%#U+=L{K~apNw$)uC5#1r(BJ;lA+YCyljy z<=hoaKK$fFZe^?V)bQcM1nXe$D1VpN);5A+>mKrf$??NZ5@7p$!g1$aqtDJsML}KF ztfzBC{n$@1llMn3$*(FOhpj(glDlxMomUUGeHdyzDSrLw2R9Srp~a$%H$?}PYoGw2 zyndp2IRz11+@9!)Dj$f2*(2?G@_MRD5jf`8!JmEW` z4cmPMtb1dvlSlsUAQpXKYC;-6dVm-(AQI9z4R-yU^np5lh@IuO(8EL?U~>DJdPj?+ zKZU72J-f;8%`@~d?3RUvqdBT0H?ws{6Jn>POJf8BrZ@IKtwFM9yejRS-P{A2^O{e> z)_H?5S7(QH@=Wx!Xbbyc#0iJwVZNVlV&hBpug;y&@{;WlU)XFg

16EF5=)ovF|7 z{n>8BF>KHKV^=&2!5q5ab=8Apm(mlav6(m23dbVyfp{%V6ILH8pMnY-CFws=*vYO4 zY{wdPqrGUd33j;;Ood5YL1DM*N)WlJ`BPHyYlDZ@-JMPH`@b&%YVZo98Z`dCDlm3r zcIUg~FeE`H_DnVV1fb~&-8?yH1%P~Q+l}Np|x4IH` z&o2mu0qwq2f}p+iiO0gQ{E)6QlM*`QorAX0pz`wDH{R@=97EOKmc@;0mG9hIxweR( z7SH8-aUrjjX@tmzqC9&U2712ObHFyDWlx_t zoe=Z95{eP0^0=<@>$JEI;egh;TFIoS1DkCX6WiOxKq)>J#J(Ls>Y1CLBvvX18GPvd zks`Za)2b)RU9zkmXEX{@ICcoeq)48=`B-ffYQ4BfdE-tF!znP5;{PeX zF~VALP8Fp>1svsZ+%?|}C)3@hvalI1h8Ee2#o#AFJJ2{LXKJ)x8gz<=(+EoM|cs@THT7jbdHN@Oq5(}+ImIqy?(+~~8cyYukAt>UMfd`u(K zm}Qj^K(@^uMJw&O-}3gl^-aCp&E<)5AYRZ-(xf_C&VrXgsITY(9|=>l4mQaRHj^CI z=8g#C`;!p8s(PI#*7}@7C2w?nk3M5f3hmD1l%ZX?ZY;Il;Nn`HKYw%cn@!6L(yDjT zMlUO{vZL7*9Ym+WY-@-aw%&|`3x*u7;toAs$Eqw9lnI!EJ{W?1m1shweUfZVsdFz4 z2xQh^-&R*rimTxqGmo$`z|)p>Z)(76ks`BZHgjVsld zxO=DA@s(b{?f5ir(<}MZpG2p&r7u7B&cw(3@EL^8k&~G53*kLjoop3p!X7#gn&?Wa zoEI4Wp!gO5A|usqp$%#Zbb70wUzz15{JR0|lB!-h)e-};z3@_e^YsT>&iCbFw_tnX z;oL`B7_gYps7S;PsPM~9mfY?2emX^&40ceMy&T|xmjqwuq^{? zAPM*|f7bMlT>PbJ@^k|ijmQU^B-LE+7ct)Koqi@5JH_G7M>Qe{Yg3VCb9GGf3ovaXoOCwr6javKZC+S_!Rh2Xr%FS-zuiUJg-rIx|M+?t2)X)zu5f;e+r60j zPMjY%>MfyHA{=1fl`4KK88Glf`~yVcr+a5oKQ^oVzRd@IL}o?0zOt`_4iE8ppNmC| zgVlVstbheh*t$F5J)e3@$RI9SR{5?ot`CCp0!zyWJkJEvy?~{24%10@L_bPlj(n=i zoF6(Ga64b>w5Y=PVX8dmE9_-G3)8z+L&nTmzyvr37QD#SCLYM=(3Lzr_r<}9n$C*G zSeL4MFxL)G0fz0d2!(?!KcWzCXt6tTSqGg%+E#&+Jm92p1Y+{ajCgnla1>fj?t%1n z-WU1DYBK90fK6f1$3BbB?!fM`d)OiEg;S-%6Kq50dAk^){CCw>C*| zk+Hw?L)mkDjB5ySaeE$m3Mw8%!pX#v|HIZUEs{MKFF$tHL`tu8yghVP-Dig%ay2UK zXlD7hA60WyQ}C1Xw>g-=*xmQ=_#x=z#mPj5tU(P7#?rpuQ%=<^tPQGrt& zT=CjvKJCr$3!>rB3uqI0uxlWWvj5~d#&YJqb~=D5J7k{3uw%m%1RKX#OsI8iWsyLr62iAY__o9OvsRY5UhPH`T0q=ZPY9x zl18vnEjPjY#X06<5wis$5FA_PH9Z#V6@nLSR0A%j5CM#fs@aR@)x{WNUxVIfzA#|) zjb80PqvH^EPoPZYI7^?VjeplcaOus*m#Zi4S$!-faLTN)Jvx8F@$98HD=0{Y=K-@O z5EV_nX}~_EtDR)1yO(21UPlHXr>9{IL*_aJp3k<7T#~)g=tRzizJ&8ZCtD;|OH*&M zuw<9oH74cIE}di_T<4x(krV)f1DW2_|DrtGmaeY3T$FGt>igO3I;nOj+Di^QI=*q1 zmdfMJ-%m@w0cpVK3yQz{-#XHJB@)%i5Myzytww*$S9FtAC=NU(?o<18Q zr0Wc=Wt2)gL*YcPmKt_+T%-TRU+onVJNhQ1DBje?%Xsw4wQ)c!xMH`E+wP+j7$0>PNIEo1CVlqUh=(fz?zpV1Zu zeJ8yz{VzbiAKT)ng{jDhIJLZQEfkt!$)N& z5vy_v>Hvqv!>^M4)@(&$u&#$R1q zVe8#$<4N~8@vyF*7sRq_q_p2H>mCs02sw&vwa$C-EPpcX*Y6bO{M2^XyCfjHwvoZe zYzbs1xHea6A1b;T3RP*tm3>rNlf;btfsG0%-?`-0M!86`gjuW1WBHTfO>I4LUh__e1x;T;;s?Jx+9**P(Wak6G;<dLL~k6hX6qJWf)lG!%()B7diN9WwI2_ zFfRmHC6QB#`Mho8PT&yr37ofO(AFTmuO}v@BP($6Y6#XP=7aKJk23Bs#(bgpQc)4g z8x{D?Me^cCr#^B54xYG@3j?%NSH(^d?Kg&afNl`xLN;-qdZ(JbSJ5Gs*7(G){edxgEapfF?tlhTZ@6ig z9YQ>_wtaM&94}HBPo8#%hlhuf4gS&i^kaX2zYq%6;rMhH=d;^~D7RG4OI7M`F@{Hm zwButG|2}3AMhCd+L|tB*YIXO?SG-^gEJjBJ8D6@ux7ll zd=L(^>VQ9tH&CMZZJP*_W+k;6rY6kxUb~BV(K^p>${DcHDOWPNk&$q7P zYQ(mr#zqi&8qdQ4difoB%}oH~j{~nF$E_=)p!Jj1sE zxzZSuDQG(aNZ*$ijE5XQGicWsTnRSq67e1``;i(yl=pu-$)oR2E)uMR)ZylDFyNH= z*c>y-vmyrLKT)uzzRfPtDN?_=92aDql(+`|I}+a>u#SfJEryY*p4J8PrkNCC(k;bN z)=b*)yQ)gebH{Ea+N^gjWTU236*${!+Os6guff93O7}_})xvs*y46bK*_Is;!2^B_}DF2Hcr!be=QJAW-X^BBH#LrseY}3#2+kw;J5D*n$DNdT*kDl?=!(G<1(Zp~+x6HYVnW2)0NF!c;X< zB@nN3`YiW723mU>FD^3}Q$EmOaK;(i+n*OW4z!qc=Ia?$puzmXk|h}~U^gcQVtS7K z{pH6lHRUNfho&z{%mCf^B$tlve%WXx7U0y?3(V~y@=6dA(TR0Z>BkQ!2F8^;iKLb; z+=a_cO?XAS`OUViKpuo!8PDauz3g{FovY3Y()#O*8TbS0?3R_8x@xLlb-m(@kpG z3-@Tz0Eu0dm(`ZWz!zZu9 zY_9+kC{T^Wt zBVCKc{JkVW(f_H@zT!odF~o+LwbbV*9;0JQ@asimk8*Po^Q-v&%%|D^yRA zXwgwzp_xvc3%0@xooYF%xd{o%=&mZ*(kXC)^oy=tJ>swU0M`QR($KXgWo5LjX)yU} zFiJwLcWllp3A7~y-cb-=T40kG;2)qwkF4gj{|{Y%0ar!W^^e0!cS)y|96F`*(47L( zB}hn0cXtU&#}O%MrBfP2x}{4(x+Ubl(d)XO`+0uv`(bp>(V4Z^UhBJZ?-{6j@XeXf zuiP7=3rpd1x6gJd9@9*NMv290`fSadS#DK3 z;`F_j(-cLgFRbb@Jv+#)c#V6MC(X^2FyY1d1bBUpS}?^YMt*loNR`vl6>ZI=XK?O5 zDmol>Dau|(R(%b#B=y_DdOLQ-3NJXsh|WhF-;=iHX1R)_Tt=*^BtpA&TFM>|H!{y% zorNT|t^f^+8i9og=q^xxoz=JRL_cVMgqadD#b`9noB$QpV~!!a*kR7$q`EvA8SN+JrMB1#OxUixi{7X& zHr)b*KJRn)rd@n@3N{V~TqGm4%JvLrxnp^L$8MZPp>Y-fH2O!KSdmmi(bkM*Y8Cf7~znEj!cG*_ zW_V;f2W^vb)oYOSD)DCz^a(uly|w@2Y3_2rA5*kOPTP@B`d(_)vkvw65-QAb~Y zf&38LtRyKS=O7Txd0qBPa^Z5rdSv~jhl`;7n9O8_PK8lKz;vJPXP<6)1D%RZUrv-M9N>IBs~TXf`enR-?da$Tb@MPB5AYEcR}NWT zA@@#UUrLYunSQ=Y0^Fz<07rUDw_7tmCDY9We4uy73MY9Dmboo=5y$zn2$J{?#mu>k zN~__A%)fE)2`DH?DAiTIJQ6s!o2lf)oF>s=a`Ykia z-+egiSv@VT&-a>MT^jbk+iQ{vikQFm%2u|G=ngS~Xc=btezNc$VHC>h=50t(d-k4~ zl41mhMgp?fRLb)50+#J!$wi0ZTzd7f^IZ!~?iuVWVO(Wq=09!3rR-(o63AvKl1jLz z!_nB4#b3E_dW0-4twc+xv9ydjo$3~aUbti`3;69=WOL))ePGmqnaRn$1jpm3IAMPi ze`v=d`Mg%1b&_@s&tn=sI=ViJ<|AHG`)Nr5#c>4T3u<8rg%5f2M`mhYorbx13^$RD z&4k>~=V!^vS8}4lL&8GBv?4#22BHh7JfYyPyb~w=tyXTGRKQ6uF14>9mmpNhvlw5+ zE*a_@Tc$flNNLi=09u?7-t%Y4vm|K7u6y&d8AG#&e14O8_gSpsd&mB9`Du#5b}Fee zBuvtY3b1Os4`RFi%;-1M8N)|Rpq3aBpj%H@7E6kTkFa?jvL#DS(+87OO}S4Q4St;LM| zTEnWErK@ZRN3OXY=RdGI_tPB}i3a-hu3_Ikszl7P0Ww2iD5LB< zoU=MISO+@Qa@?R^eV%~tQHQr$!L1(4E+P$$b5z3Pi#LxxW3$JFqs^WraU4Cb&qLlc z_hrGKoh6>c0yF>9J+QI zj)Osvof&oA7JNNBiPAy{O)Me!6qR!Xq;uamXsW844GH9ib>wfM>yDz@Z+?bddhp|? z{UQ$Y!2)Ce1nZJC4oLl)iGb4$=xga-wg)Nyo^r0-z~Iaxf|S%c9RSg0iLAP%u_uJV zoX_+dnIqrin`lE$@krW9b(gjWU?h2f1=?2O7}oT^`|+aFZUi zJOD$zOL)xp8aCt!aKO}j_;CL>;{HYB_sgIm>&2!)&}Hw$M3ZQPiL2 zur3irM+oWPE9`$J;TAR5(cupix#0?tbr`>)1twjQNwH%}m7@z*$Nv z85>IKddQFMA6^7E#Ghq$;K!2na| zd!0pm1sWL8kU~zIkBSn|xu}tw2Q7cIzoQ0B|{$luO9CUPYad z;}9<{V^yOc4R{ay`&BA<-;h~Ys4IEi9}{^ z&Q(bARt*Z{Ghna3fNR(@j1&zg$ja4fMt%0^3}PcOZL=4SS4Eb%flNd56&s+yLB)7N zVML;sjrq{kAOESZeVzvd*PPJp;XnUBJZgsw{ItTWhDYki)eyY~FPB~nfh(aNBWDOajes0#K z4&>d6f_jXR6C++opk}iI|FY(xG-DY?BU>mQbs}_wcGJ z`Y1Ka$KT6C@o*Vm3HUCk@ew|Dm5NH7MDx1DxzVmy$DN z``z!e)%pmtf+#p4P(g1X%+bf~Cin0IL#S4r+E2)jh{LQU!DcrIG%&5^LL##Erz7iw zzsM2}wfjx><01?y@NC%n4UO7sg+d)6IQlCVacBO&@brwCq)<1{Aw+ArCJj@O8ATO% zcEs}s6AS-nj8d}4zGJsl4I;ua&R&BNrF1Le6&(O~&>YvjaL*?|g^S(GSex+IYA-M8 zVm#rc3&xo~ybXdIM_!AT0OGs>;X>m3ZB!aOY@|xgdv?ta!gSl({##FNd2`>xh36ke z5r$Zugo5Q>N@)O! zuW@Qy8GiMfR`{_c?Jrvq6?~2mfP46RMfQt7s6d;gQCSsN#*h74sAwF5hl)AkEed7} zoR}w}cb4SL3?7>AC3sCj;QLWG3buD)a1HIVEB*Hf1R^uFypRR>g3#_pt>{XFP2+`T ziY|~*XYQdCAP)gmfS)SqLK9gGd@pM_Bg$x+qka@nOwh}ybd8n&b=${0<6*his%l%W zpXo4YK1}F*}Lno-$S}m zor)2XJzQBV!9E*Y0cE*_P0ttPGRgr^GQB+0W^r5(OD=8K06a3iHCV&n5OgeT^-(Wa z6+x0@mIurBI}GL9c66O_Fy7SIv_j74eLw^;6CU#lk18evx^yP9xdDNbSFg84#rHI! ze&>z^hEbGDKo-<`^fn1o?FkSxVjzy~?V@s4iunP5ajp8zySc)Xf= zON0uI;$vijg@}QDhvMa_HN;uiKwGrnUa-K0SbZ&bmT;j18Rs1d*fo}-_%fjBop_pk z+j6h>KPeV$(GPxDDF~XO2V1m%sFU<|_%fd;m}a2q{jCj{u_l;tQFSHD-Ncxh4DVdr zTZ$Fuc)!qR6uA+3UR-X|$Y3B4fC@>^85g}M&{%guu}YSmm(F@zsGw>6!^`as_tOD* zE!Lo+coBasLE?R?zH9S9r%9_vomE~uv6PAEsXQ)FGXrp%y1s-aJ0_6RSv64g7?j`Y z**Uq@`%s3YBEqY2`Pw-T@%o34phT@8zAq zD{c+e9nOb4)(mWv5vbU}zPV7DP9T68fwEnAI*P5{yd;2Yvt%718}d-+=h367>R_(I zkI!$C?hRe*o{Yt9%gk#Ad{QpVM>6e`grWhmZ6VN32GcHC!0jZEOXckC=qpZq^yN;- zzk2}`N~xLiiI>f0H_8dbtU|b~Xg|gFzXgV1gNk}=G8Li8uM3ZMc8O|y5ngh3jTG$# zg%OE<839I3Qv)b|!p`Y6=gu9OA}snW`=wjkO{Vv)+7{HKK(rVwB0`RyS|Xc;mZ#IP zlm_3X6?35ROE-BUqg*Lgs1ZeU_$GiKSeRTNHS)n`j}L{4ol9jHuh@W6>hmMm$VMMe zDjAsC1c274icZa2Im{rgbG^t2?)GlBFkOYr<8WwFSl*x>@ar1)&>_2gDoXk=v;eyY z9(~yc-g0F?7M4(Rj?2=3E+zE=B=EzvZCKFw9hj2J+mrMUDD^XO1urcK)wZs$)m`GT zz%^kBkFnh^G(bP}Z} ziU_0&x@?pOpJ5&^+3*!!21IlU*3XofAI*oW?U>bI3}$}^RJs9`W`Nil*%EP>N=fDN z!}^(qj{*;i^K&OIQ$}Bq05YKAm+f#$9CL|+R<<3`;{?aXd&&*iR(K(s19AmGB_B{} zMK=|A$e;ivne`y@dj(IVSZvRpt%0X7xE!CVcK@usSV^)p91wO^9C)NIUInCK9LA|jH3x-s|f zD2*|KpgCBQZOQw!#bpHf2s29y87r?O z?Btm(SfXH9#1JH_1YU6)ZFFGz8Yz*_VSvdsLB|g=<}3l5NHx=91oRU z?#kof-tS*I#?ygTkjAHkL#xQD>d6dVsk2Yalmu(EJ(c`L8wesT*eJ8k3ToMk7R=Ch zi?M_mD>mT%R6*jXGrf>HW8h{NKtbo=L_<@jW%D4}X+k7`b#TQ-Uq9DJ11DL~V2(1` z015CT1o)9@bKuw}ft;R+&tKCT?EgMEy3$v(JA4h0^3N4Li(We5uR5Uz7lS)3&lwiKhi zPZ16%`B+m<2n;D8lelF7+!SoarwZVpDU$_>o-BI-u>rrCPni>#NEHy_lP1E0H;QtBAS#zI5Wtk<$bddULR^kZ`$6e?)>p)Y~zWQwhzndFRw1!iR>bcIa1hp4Bb|9?Jr~BeO4; z(?5RSLGMyVSTbo=qsOXU(rr_t`_H#h?dVCHDn0P+o}pccNB8k10W%@aG8H)f{Pp*v z$rt}mA2tNMSp)Yiz6p?-8>7O+y4sA&J&hJ%B zd|4v;7_t5g`p+=`j{SGg|9p!K%AY1X^~CUMS;oA4UPmiF=c2F{C$HmYbZ@Mwu##+hLB*^_AS_x}uk zKklT>TL`gUUON~(1}S*dgo79p>A${_V#oxyzvLi}5qzlX=(mvmwAV4KRr0`|ewhpy zdX6G2ty^ON3d6FktRylxcx_Sp+mSz6&l&su#kTl*+HURA#&^FI+X3^IcC-7V->e3f z`*#G6e@XwZ@&5kbgzbv!o9XgjXEevef+8cV#G)WZ5P6-OHw%!WmF-8Q?!lE`?C64| zGWkta2FI;aLdBaYuw(gu{g9X3BN+f3Sj`UwIYw&w56J=Nf?43;jaMm|+^H7K(k`6b z{_oQ`_{Xw(724l2w0;cvk_zF;Sd0`J|C|IrRB!gz{5_0QY=@J;#_yV2w(0XGgUFx{ zPygTf+zal%W|#Zu@I~AndYe$Fa1U~}4b$=-5Fu=BayMV|78YYyP4?4##Y=}~th@Y5 z%|_ovOL!Ig*l)^qy4+~M9Ti~_~o>!@ftDB0t&Zrmp6G0 zB0YWW)gl4V77~C12Ng%5-fJ7UpY7Zp7Cvf=QN{S3O5t6W%AHWwZ$W^G`u>;oDh%R? z!&NWZ>rx&hlk`7r4t?K5q-WP8W8x<&Y)|#$iBMh{l^u-VS8}IJ@|E4H{XVk8uC!6tCz-gk>Q(D?J z8!UTv4h{|ohpL*1iHVv?cJ3E(G0cc#M*FWm=mA*f>FxUWBuj*7ESmzjraRcSlYmnI z0rK$HS8YejB96KWt?$+IaW;c`$0M_={H5oPwtnq_5`p&z_~RJ_2M-^7!}FMl+}hap z9bE2sYQdoj(B_*z5P^-@9<2VlP)7jyOOdY^$)OzpX=&0scsUA?&H*4AEf*~Fs|MAN;Nd8o6`?PjTFhh}4dqdPA zaC7N-Ud^DGAsUljN)q0qcuGZqSbvlv-EyVbPcH_N84cfCpu$JYC%R4v6$dQ+ zq{Tesg|6Ps1Y>_G`sixfd7!|RB#xJ`_~BwPI#+AEMF&@UJ0b`TLW2T<1c4`N)WrqI z^7+ui7QK-XKPaFkqN{&N=(p5({om25U9%9`YH`>j9eleWRXpR<&^LyhW zaIIy;OzR0AK|XHeq(0T*4-^b(5$Ql*3Ekxl_N`ma0^#lp&d*P2R<_24-1okFCf+47 zx@QYFxV%t|!tt}!se^#GE$iS!MvO&t?U-rnd~)gMIQBk{UCw`L`Xj&QX61ya=rQV+%6ZxD9hP~tYu==EQ z!~tQitw(q7t9Z zlM>{B{F+JGR(_rnryt`fZ<>cDI;dF*^fW5HKauJ(e~(?Ech`9!yw0M&U+kPl0HssW zG1fysv?6%o1P1oFy~GH;fPCw+Xex^P(E;~YYf888uC+%NgCcsDuNt3~3>~ROMZNt> zgf1P?rKIY$M+wVoWWs|7GEXT#svHLYN=KC$}^)a!6zY7;?`0$wUwyPrp&i4zSVUOedvbEevh2GgbzTI{o;kP zlyKCo_0fAxVH~|G%h(_Z6x_%AXB6;HH|cus7-QwSgnz|Xwa|rK#h5Ldlvb9CdY%h$ zJT1XQbPs>LD*x?csA9#jc&px1<|on-0bG0Ze26J8IuF2&-=4U_HtaC625>Wu?f3~t z-ujuCSt)H7)^Zd-q7m&X^?x(L;>(Gp{ZB4i(s8Po2)`E)4+<~h4ini3pm)vI>B z9kUlm;K!zVwYHM_-5{{K_YF1W+l$TTCu~l}QhQ;p8jqz+1ho$!rsL^ro5?bCHj+!Q zO=65aR)zCCYF$`AG^{nY>YdBB5c$zd71i4-j0yRv9PJ9%ERGNqyYeC9_SEdl zr-0EpW^>O23XHM}nf_O3%&)V*mE>`rpI`In#zd5eXj&Q|2ia6xr(#ft_*oJAT%r9| zvX)wPV@ly0OruL3&3F4$&ZNzs^Rs+S&P{1y$UFPlQyixiBmN%@`vbpLPttIp!nw#T z$T_DS@j#sGdV{8BRv3fU(q#m?t9uvLd=%!~*|c|*$Q@QGVmXJ*I8&wO-H$_X?%w~s z$^ZT)w`7_Nn8~-UAEJZVG`cG?ake&AoJ!khV%%5HLgL-x(@5a)cc*@!g4?V|Oo(rp z{1mOF%yeFfpr@O>G*HdX2&0#|D40TvdBvWWM5P#f7`S-)n^gR%M}8C(<;WNbGfY0~ zP)C6lujy?KW8HJpCxQbt2}x;HP^Crg(vqmEIO8#EypB|(b3goqn|yl#9OzA?L@=t6 z(Ic^Z9-69g>5HSzabi;bkVPu<$n8DG8hR8>qLXh767K94K!P>$uar&|bWMgGw^;I8gD zJL7*8-ZxA%gJ7m))(T?Iz$LcQNUo3qj3c>lU zY+Es1k{Q*zrn2!Wc^*Gb3=Deddm~8E_GRQqSnzgRjYZuGv2(Fw#@*HP*pYvg%Fcrs ztw=EU6BI>krR5QYFT+)<5O_2YN4`s0y6o5jl36fZM$H0+G%oXVyXWLx8POX< zBaRXresTa5?%XHJo7)(~Hnjna>}HX{(!#jCW9Fs%?#(BZs}6fxZAg$4iDw~|h!t~t zZVe0eDgQaeHFzHcHeFEGdox@O8T#OyTEx+GM-e&VQDG&w$sfcYNh;97i7#Pq--(9R zCetnjK4ux+<2K5UsiF-v>%@8?c~gV#;ERY)J|#}wWe)pq(tifJ7X6>G{xkBy2@YS} z;fEFZED3B6a|6!uRDHfn)i~&j5^a@ET77+?cMfE0{>d^30VlKbs+qA}YWWAxHK-H~ zzWQ>%bT^G@`OP`_gZj6^w?avK$@BJCLAV`6-#47Q>kT;BbYcbw)|?y649ba9n0q#& zoEA3Sn&$262KK;-ay5;c#oA-+@cKS;eRrW;qX&L8pxY7>OPw7b9Ft*&( ztR?t3>M%fWsHecF|6$<2x%$K4U#=P=9jLLw$5$K$$*~GM|IZ1fiCuoiSH1%pe7G=q z{|jFPcQ*nft_E%CS8%u9oj}?~1KZR|aZ#`c=}u6QEt^BJk6i>WP-^0(*xUY*3!RQs8f&M&9-0KN8EKj zH7i2TCeg%LX{(+CyolhhHL~Ap>Hn42#*=LROqhyQ(KyM@>oCErKOeU-Tm>bwhSUnV zC;oh-PzjebRh{Nzef~P@`jfjCC#zG<#|78v$Q45`*~MH1QPRY0U^u*aBKGd3*VNNgW(NKd_e@<$#tZ-kibno3(*2ITDUJfh%-ei{9=BP3{-i7xVXa>D**!UpJS3AZZ&rMH(a-M1_Xx z2cZK=E8YFi|DQvSk>JDcOz?K(8XeocNj>kHDWkF$J==UsIJ}bXB2)kXwsYH&p8~6p79}4)O6+CD zCQNr&@~?&>W6!#Jyv)o+s;aVQbX7|kc&8qb{RIEICAKz+UGz9#D?vj-0g*93C>c$I zNv`;Deo#$j6F5lGeNE1Cq1!b zd=B&VPT<4+d*|yt!~F>)+55qzOMiw&LFnMWC5OtuYYpzf72Ba@l4?By_vS>yqY+8_+R0m}` z8r;t(ipSeB#r%I0`qO~l`*1<8m@Vx237n%bpb;U33}>y;Yqz3kOS`NjKj%}B+h9C2 zCYeJU^1i&Nmao(HO3T8ejWQJq<%y$*{Nw1)Q0=^qZQY&XJm@1r95*jV&1K`W1c&`S zX$*J3F1bR5w}Q_;YB5rvn4*Wz?T2U^KWXQ?l^OA2^8+=_@=NY$R6|al3dE<{risy> z_Qe$4oV<1P0$3rqedVpyC}`i9I@a8NehGxX#?Dz23$^-s8IB>3+Yx2}FE)|N42f!X(k@e&w5V5-6)&UGwhbBa74Jhk^SP4|R|^eFT3^fQ zA;asT9I;Z5uAnR+-7_QcICCS>FCp_$hr<3M5;ZI>f(m+K0q6+GZ7Awd&Sqj`%K@ zhbG~hy>b}=apOCB!CfUi7Uz0LyP1_z;_KBHXa^Y7haQV$@B2AEa~%yfnQt@}5mQD% zG|LT&F;G^f4Oj`+40MsHSYC;PaCwQCj~htGdtrT!->#OUjzJvs>?-E{FM}A*0edSY zRk)#i-k-TWr`25*(co8Fw0@O*&io9b!$C}alhbqt*TI|Ind#@n?UJ!Z1f-ShBm#1M z$+mSzF(+QU==naENX)ljT>)Q}Tv;+;c79bSDC`uShH^VNn();oZ1*kmv#((|k)cg{ z!Wws(=q|P;n)_BaK_H&tWu4g^MwSwLtuTx3$381)mP(|cCjNQ&lwI{n?w0CO1pV!< zLKoG+a5N#sW}wBS&14@S6jd^X;WbU1uqP45brn6Y~u?{@KBCK8eng5iSO7 zRF}=Fh0KqaK8%#r(gwNoczpbW@H;&7yeqZ+!pCqufd#V5gQnD7Nu8f9Db`w-qhd)d zK~cP|)DZnTJ)|nNv<;DBIF1SsGVzMB+L|N2Y7qW~g<$%&mU~+i%Y6TR_+_I=;A)17 zyWH<*w5z>k0-EpZht*4-FKD48dhGdJv2p90+ieLo3zCWf?SIMqwx{g<1VfU*-$Y%q z^w@TBD>qA;v$g7>5RDp3OIPTE=uo?IGHM`b;)Z`N^&zAy4~A%x2MN z@&T3#*&bS4VltjoQf7k4%!^c)d?@;;ekw^qtDt^unMTol1KR}dz z+oSa>XVwUBPLmYZQG5D>QgTO((Dd_j!XB=(cjI@yF$;tKVWF{d^Y+4R#5=0qL9+SN zSaS&c`fVC;)NuU~e)zNdUq;r4UQ>ndF~*|sH(pZmKI~w#WVHY)Fm^WStB4N|vW-L*s<1bD8z}=>YKZp0cu5qG~`Z8-YMOMpB6!zU0 zxUre6v4}5gL%w0Yp&UFOI3m3!X>-5)UOYF9pvkB5tD zS>Pw8hEqQn<;jYNxejYw3*B?^fOI^1v#n#~K7eH^$G)(vp`QM&7IQ|a{MnOEBSpU= zxHc*2_@!HO4R~Hz=&(q#j=W%KMXQr1AkAP|W7==1W>OfNji3cs&S!Id%P zHzHK0oink*DZ2WxQr6z%pF?7HU>c>n@>Wqv!CUoS7(z7ulzl=_g<=sZC#; z-c7fE3xsOThurfamGWsZn*RbJ?7Qk_l96s@d004JZA+uaFW;PNgMU>0|o;wZu7wX@jNw-o$vudQ*{8hUh#EfnX|h#!8xT3M#(XHs!|Y~; z8AE(p!HdXcbn8mc)(N!MCpjiZ>re|FWGM@G<<)uIJvu>5HVNJ`hacJdzSh03L6|-M z%hO$WzGh(>L})~K&&6_sb?P=>P(Qo5EihiKx3MgCAuxJO&nsk>2|vLs2JmX^Lw@x1 zgqKSD?~5xTPvcGeuMHEdoasU11uyHDS6^BT@vKpLXIjk``|`Hs5t=Jv15IxUoC*qC@nXGh zTkd&KtU0?mu|q^QPdyVh1tlLdIr+DePHIpCcWfxgo>x*yg3!@PH-& z@9Mr+N<+fh&q7@2O$y2I(JFq-yu!wimx8G|5aU#;QFTTfZ0>mlBGqtMC@JfYSZq!= zfobKM&&0pkYWEC+T79zXudDW+dsx3lfJWT8F?0?dM&l9}SA_wdIe{dZ1%FO1ug%^Y zImixRNr-0T*T-hNYtzNm5-Us1!^2-VOBkI9g)E9v@N@X2QH~fImCU?^VtlTcI%BBJX#Q2j}<~Qm4ytte1zjw`6l=%lJjC0e5Tyl$P zeHewtkPj=rJ)21dZpQVg?dzGeYGN;QI)}I~Q1|03b0_#1R(q+qVAv(+?GL#iA|ARS zZBh47@LruDAPC0cBqB+6Su?s#`Q9_fUC@ww@KYrHp(Mv^>I~*pJ2V!MAcB<8R6(pM z8`ojAchQ^ZX&$B%!S#@1pKy~fG@@4%?Ez`$Dp7AlRM>vQmC7w zgvo#I?;tAJp?4h27dOY^ErmZ~@H%E@(-`(5r0xM-Eiw^x<1qhy~Y~+r~>?&AG1)QvlwAX47>y0HiXAo$UPKJXJ zRDeZv973fUFE*>QkG0nLh^XpT78;273kRAC;O?SlLU-ZRJ1J)e?$6DbPqRGXSZ8g_ z!F*fwrexU(NK^L$6=ZT$4MtZ8!>Z4^+Be>j22QfdQ}t6BzV_JU^pS*E4CaAq8Np?2prl-j2(uGMen#}^ z3G?HSL;1l;@~`2M8H^&H*yfr5L5qVdeB^~(rY|*!(pkP}Tt|7*#^v`;v@}~ie+DmB zRVpfB`*F1?Rp*Ihs3!>y^zz5r^siHb7~vDz!p~-^3bbANR3lb&Vf!2PUjpHDKmL>w z^b4#?d&StyOx)%O>mv~LqFBnZttIe^drcE^INC}xVHlQ34G-YDD{mcg$!e?Am6l9= zb?N%uKQ^Cjv$5C>zc;yVo>$Z#)qlCHB|QwCKy+?ql}r9fog~T%ch-^Fm@O=IMkDTr zOBF*tZjgNrr^SOXd#eUYA7Qe0fDY3uwbUyZ&33%>GP2CYlg`D7ONDs9amjOsXzGxN z;LXA+7}pcwVt-X90b+d(QfmIRxr{3%4Gc_5sk$TGuYcm1NohY639IL~TZ(H{qhM>4 zr!~?(&u6~DY#wvK)9Cx$62X;UJ0WH#=$03g-9b(qc;wzK= z+(dwX-knt4<{)VLDH>>|4!hjaT`;Fh8$|%46D$qp^Q7`;Wm&cMg3%+cci7jW(8UeLp*X*5-xwIhylBxh4$;V+>yuRxNqR^JhJfBUJXzV7@3Nrn>-jZBrW{QdP` zZ(W~p=I8v1T=A_c6M11!S{~;h>PsN#OBjN)IvTS-STxO{;R=t8W&&0ax+E1zHJ&J# zZvC>xIEbz(5K*n#Yft_D>?@hyrM%saeR1$9Nu)zhD_n~#h#&D=CK5JfU-}p-IGfpd zKkz_>*I8@hYbH5f)3vF%Fp(>IDjrzaAjg~$t40gVXkDPxP-#E1P^AEb8$dc&3zwz{_F1YDGuy%T56DbMvW_4U37&nF-!pf#TlE} zsmjN@xck{{CQbKM@;zW^M?%j&kr6@|qtY%O5&d%lP1sZa3H4{Fyl(6Sdc#x^}os5Ha;G8-s z_3u5E+JPNM%KNqYI9h7mpLu-6tqP_)_K9mgQ;6OT`a6$->7l!4)vW&#pa(PfRE0LI z+}U^YHb zoP@TV@xTF;Z}Ka=ax-~E)hr#>QhXFxvZJbH^a#Muk3hJHt)N?OwB;rpH{)LXofQHG ziB=jWFFi$~_Ox_=TKMUJ2e65oG*?mJ!%VQnw9kv4P9AoHrDSJWy%3zE(j}Avw=aEP zsFikO2JgjRd}0CigGe@hb0g&KFstxaYT8bnJ5QD^D-EPDU_57r2ahJvV>ESLF_Tk&S>v#;ryU@0Qw>{hA}|;_IjXB4cDqALH<(_> zNMmxkm#teHk%dlbPmS8V!1Oulx3!qbAO&lXmAND!Rkv_e{;u3>bg%ugerS(-X98PI z67Z%o?|ar~55CNwqp<;$>-B!U8On7(>dxk3)7FtiIpUvJ*!$`uW7_fdhh@|f`Aif5 zK-(Tf`p23I2J0*FBMLOz?XOEGP7XdCRm?**!zTIq8(3p6C2&OR|JVUdh=;IEnVGwK zOm%wa71N*ljdxhBjt7Xxz=D1KL&7Du0T)@GFBOyRt+UtpJ0kclr^ObixqZpfq)kI zs^PHv*ehfY5`eSHDUcL9rq6loojzm7K;U*ypf0^6?fXN?#&x!L6TN0SCkE!`^gfPx z9S@nxm4c)}?0)IV>T{&OGN7~-g|k}4*qCxc!lB{I>K$dm0L;(-dfVEW3Zs2wRVI0+ zymDqU3sOH2h^>;+B9#@Y!ou0~RB0!K{q+LDgmEc|J-qN?oWEYg#2mCQ2hKzS`T1)t ze2J+g9;0{rTun)M@@}rDX!@|b_G6tjFEavqX~o8m1&K?GUFHvSDM-{^YoBXaTvJTf z4G0x>zo^{n&)l5g_yE0U&x-DHHE<}1d~x-e=$L3^s;cA9urGiIlx3KyXGZcO#n%3Kfe zSocL`DVui2bkHfX=5kWnp2$QFnGBrX_%fv{VaQ6-+ZxmbBNQM9f}|hXUzea9u+KS8 z1}bsBz?A)0n;P+#U>wzzsQGmemI5+X*c#ELrPBa06MH0GyU%35@~tQAa$O^FiFghk z(3mo#Bx5%HFimV((;*6EDFy>JXf1-_skm$U+_3aqF;E}uvT&HZFMJ=(8sV`$p#;=N}hFZ#grg)+wW zo2JWJPVE!zo5*bQ!_mO2LX_M06!A;2DQ}dkYGhGC-DApupN~W29!ySsuE3E2y|zg%HRU|kWEBLJM2#|dBPm1l`cJ9qj z@VBS-nY6-3tfQAeNyHhl$UD^r4Te7+0xXeq;PCN<#RGYgk-d9^zd z{C+S1hveKw*gACTcFFQ_kn#WH>MFykY_>Mt-JO!s-6f%<5`uuFbZtWE*fb&~jWp5{ zO82Iu1(fa%C6z9}+4{ccoa_6w|ID6Qvu4G;?lsTzcpWD`q>H0BnZ>nh{}3_CL((?9 zqfe-CFWz(6QbGTX`raU{b0!QZgS@Dr_$QjWQ;8}-m&5-fi~%6 z5sUA|#REPQQJc;r(hm;fqCyg%>p$p;ch+2si}eYljQ26e@+VcFH0-r`UcEF`yg2NjOtT~2#v^~mSP>FQKQ732fb#Wh zm+F!6&C@-m2g}MB2|-g&i$_E$K%(IM@evbv8?XPjSkSJ*apG1hS~oXv@xy0o*kU9Ee)KI2w+U!60UoTpCb@izSG9)KH*KjvMg zyrK7;nvc&-E_a?rf*6WiH;o@^_E?+dq=jN&84DXHkvqGf?k_#%+T6Q|E7 z_hL_OI?;njc%@83#Tsip#xp1m?l0xt689`t{ye8x#${AQYDu5V+N|wTbi680(9fI+ z2C5ddZYb))$9ixby)#kFR1Iz7#xyjHX#83(YtrqnG~b{R!F%%2Dmvh&n`wQ$)30Cb zJgE{x(WdM`tcorBSESwj?t%sYLc_%h2Vy$Ne$BBv$^*C{>23&bd^}LW z^3usvjm7mc`oi`tMO`Ym+`Y(Y6}s@!K1E|-`6t~{^J#ILR8oU$!B=@HCXi3Rx{QVr zFsa1NX>ndhokn6JDJmG|VPEIPvq+gq16K@q_T+$sM(#%1&NW?Q zQLWkiiKQPymIt$n?z+tAVq}gMJ!O3^9t>uRyB7s8T@nw3SS)@#FzUEHn=dqtGu|}S z9k9va&I$G6-}g>Cqfx+6!|{*cm*yA9rw8}+@Zg5B2^bF2IzGT)RRxA}({KfbRIZc8 z?VStDI?ryd9lqeysaGF((UUs)(votCoH11Rj5Ke~@Xa3h;ELW16ddb0h>f7hGFByS z*%fQkMK(1RyBS0H`huXwW+mR33UY*Y18T zQd4b})VpJf*+yj!tsZp9Intnh$A3hTV1i~j1DmWnv%ez185<&ANN?QE@hrS&e zD6YSWLOOL%9>Y96M$eWXoq6c{ub(d*;R;4yTJwGOlw2nS?b|Cf5rFOZDkbkW9Fr3_ zt~po~Fn;tDwUBv>lMs7qFAjNVno9#=bGRH8qV};Kh`Jl=`C?fTA9mpCnDhi@mb$%O zpcY^Zt=7KY{qP|wLE`?59?lO?k^k;7auZz^`8?5A^$kM!>iF!sBr5BOytq7*b@WOd zgORH)ms0w(#S1@ta0&DjoJ?Tt2N~3J6w4jw%3q4fy{sOGT4r9RH{GR!HUlj(%nBF| zi=bu+P%vNfc$Gc(=FeZ==gf5tPo-r{gxNcM#9lmS_OcA^!p|&mi}m{<$Pij>Sa(V@ z9G4J`K3ON^(-Z%TotJM~ zFA2ZRn~TFYzRUS8Z4OaKa2{S^Qzy3AW&{ww9vN|>f6)1I7o6_OXQVjK3l4o&B#I*q4*YJMg+xtWW}xT=yJ|rnfZ22STFRjWofN z;7`PLPmiCGt8?2u%vEoBEmlQQXRS$5&2!-_Naom>C3y5p>Z#1>a4p;uF~SzQXIXS7i=O zP>!a&W$9yN6LD)^HJOO;C#kP(nIu%`um}I(vCvj3ZX*bd8rt<(ZTqvzrv`RA zt#He-D?^zd!C4CdcSg47-V|pAeXYAplWSNQjC%#+7Jx%~I9ri9@}?K;M6hCuua&o` zK82+_>fTJ0XFmhGATRbS_ua6=+>6#s3`WO|Uz+fU6oL+LELV|`LYlbo*t<1dH+5l? z9+fIfUhKJL#>@99Gea3?%^X*P~JT;}<~F((07k$}uW06kB(^-@$IPaVJ z5>;=sl0I-*o$0&K(vZ88^cLu#Kk-g=gOrW6vha9IGPDlp&9d$D(Hy&a)~Gk{iGj6a z-|Z4#Ou?biqw1;8bm%Kl=2;m61jl($ppLg?b4#NwWDwG2fj1Iq{rN`4xHbfdE$_IHZ=0b?c)}sWhsk9A)f} zg%6&K%6~dQ=)-#BIT zs(ECtrGM>@NJ2CBH~}Jc|8o_}*Y+i0B*xH@{rd|0hkQSsbU+GM1qROh`6U0$Gwn6E zSCZAskL9#3RY-%arZFgPyF*bnK_~u_EJ_&Wz7oHx%=Hs3)~w5BGW$Nh{fe;~oz`k| zaYv~>;-b0wymMx%=uQ?{?^?RtYwu(W^Vfph)U+h4JjN=%g#VYH5)`GM5(=6=#)JPQ zR+;3&6MXZ+Q_u|c-?ef%M8;~H6M573y=$-P45{pC!(1l@<4t$|XV6_wh+EnKjoXKI zp+`|5o2N{5PlT7fkS2N^<86&Eh53GWj+-`as3L6n!zog!#H%k*f-V<$x6Reqd`*tg zbvS$T-@5?zAG#F4c3s+?R1==dr&F5%}W7eX8 zAxc^|cJe!Umv=JPSorVDpS8I8_-)M**IE7I0I%gNacwdSB?xfzmX^@y0u1T#_zweR zps-nJmqhOX8{g@HF9`F?5Ep}wYZ&;_&ze1UwYALp-R-YaN}lseCFL8Q+PH)MguAEq zXDRQe=4-YlWgq$kz-b+3=X{=j!2eQkoAgx@EGN^j$--YKu>X0p?HSFi4*T6)RzU!t)0N)+|6if>KhO{+i(szx>7 zT?o;o`^MdIiY$I+Svv{e#GUuoJI#Ccn%%qS+1|A|_#TuoX`oA57(?;wNd%xo!Ba&{ zctCyoVi~wPg4qQVPs0M;4rP75Zw%72Sk) z>9~O4J-tEZQol)yT6@n08pH#*&r%aRmYThPY*iSEx}bvV_xShJe#@1Ccp5cTo+D62 zsr)^l?;zhm(JnMHdfDAr{~F8UdrR|%%nEom@Mh$DM(YuaGHC4I-u)Sph=2Xnma)iV z^Dupek}>p1^jv%K5qNZ&RdZ_tTqg%41tFWK+jE98uA=;GrrTpkC_&e3+j5d$K=v^z{Hq3;_L zFck2%?7`om33Zd+clZBHG5$e>WSK6slqYeApA0?+Dn8nC)vzc)yV~)hn1kYpDYmun z6?hJ-h-agj7}%l$xHq>%F)%zuVON{xR9FqFG(vp``}o^xVx7Zwm0wL5jG;NRkCR`0 z;}>WW1gtiEjxS|ZR_a>ni-RwtNgQq0BD z#wU#6xrxHv27s#`Cis7E5HbLjKxE5Q4W$@`&OvaWfgwJSl~>0EJVf;7gu3(O)!zZc zmloY|#eEaO)^J7`ICb)`boMq<=69Umwx~bkg4RJW@J10jon}80Qx8ROGHM^CjnyMC zJ-@%>;6=5B!(2k+L2tNHxPQD`>dF6a@XDDk_7DMe#O=iczlJUDG_`3kryBom|e-mzPvU}lYl?f^H>wu zK#sa^_T8c7MpmBszFZeT7IY&EDI~L`p{1VTU)@B&*=X?;7R>Oxajca4)pSn^>}T8y z+!FMWR9_tS4y!06RKN(-_L1y((G|+JU$>D;dru6$XV3$lV$MsWnob=2K?-J3S@MtL zm9Tg}!X=`2uM>cTxUwlu<&M`J`cPu7D)@d9xHoM-Aut2aI)o5q0$5-2ikxjSY9lRU zI#{6vB!7(GtB(R%e!eCqPW`s4aQzSh-;l#Ot_yx|5>G=iuPNLy;3cCeD)VMNMB+Xs zfQeo&ihnjIX7&e_Y9tSMaA5*bWUcE~PviIm91+%=6UPAXRyqG(?2#S$@oMNImmWT# zvgnjdEGR*`x1{N9C;(_u%|qfYsPz5OrN~OH1DfxZ!9psRIiP4GmiQqKXlSA|V6y9wVHo#^DON^0Y^x^q)wh_g4^BGrtA6D1cS*OsP4G)`4Pp?4>L}Q zQST`|B_Pb_XdTeyWsV^u)=LQmV5KMeas=MF)iL$VojC&my~}jiMYBqaPhgW}iB7c( zK#a98ptGuZ%RwW1avez!cJ9`cIkgT7D4Nos`7MtORGAfTW(>l(RJ!=;@;E7D!!F|?QbW7Y+zMbdrRo?9Mv9<9DykH={qxU^Rq|i$*!M(U; zjk)I$&lxFXS6Vx!JsQzg(dJ2reHLz^;-N?K1jW~A`d}{X@E&9BVAJk$@BGH#r*0dDkbbU!CQ{7Fns5~%XDuIA6?a z{oMCrP*RGX_z;co3B%ZP(Xc}YG}9eoPoX(_)TdT1EIC*n^$ zp6xvv7;#x`saX{T0y*#R2h8Y9kju2}IvJny07XNoqVCHEYqiUwi?(6@nZ~ipAoCL0 zufBMjaicgWk{v;}PUfqd7KPuFrSG=aPIMR1K+l$&(hbaP$TGgCnmy!-@KMGmEY|oD zT3@aRQEyjy;l|MxNPES50@D{pPF<@y4*_HT(R2DMY`Q?CJ0`GsLnk*vnRX-@BOwEo zsvYoR)bsiIr{^Y!IgUR-Toq0IPXJj}jTV;4&li;RjmIJ#q_Q z^ouAUjjzpJC>veGDBk%Jbd(o~FyUJIoX?~kTgH3OPQ8UP0KU>vS!2e|WY$Ve6|Y>2 z-iVyyhEK=YgA~jhE~?O)j*uJ-+Y-Hw1JB~i;Io#aeOuuHxGbiL`=K%t$5R2>}~oI zG>CyWfI1f|uMNhnBzijcTzovj2fL!TCwdA}S)% z2vhjx-Olef?h#+`uwj2xdM>ZH;nuxn{#^9J!iqlg9QV&ki6PQwmIse7oKJM$+xP-$ zoJXbKq#g$If;YNoE+KRfP$`~T4LUtECc(?0jhcTm?Se{}&~iHm?oS*I#9xXnpxiNl zlTaIh6?&cGUGU7yIUWPoauZ&3vb?w}I_edsx9~Q-2mum{{tD0A{r>7`k^5V`xer*% zzCoi?tGJsyF18Q+&;zfyZMu^-K4tXte7{VlP6=MGq^A)wkwb<%6{G($^l;)~ z57$0;e-OFvZ;4hnHox&bNW;rNL#mw9!_{QMkQ>^eo$g&gy(TqZA=~$lloo#WW8vS( zfrBhZmOk$u4n7=wJGEBo3iMJ{k>z?IyArKqV`h5)0t(b(dbkj&lcLn=i5)%}zKxGS znBXuOZV6+$Seu{}o1qDSt2fotOD5Z&0#E8p$cH-$jWEF|Sw!Ai#4kYvdvp8<8Ej}2 z3*C#F`w(qe5C7R4{zS0pr-GWjdh}i7{`!ikn15Ds0p^rKbhKFZz95Yeh^xK*8`;zZ z!8EhFYDoFd5xErlH>}(`tiU$-cMKMQkyoA!fzJas5&AtQE=3=WkcAu7`L}f2rcbzj z+tQOgRyn|>VmPmyU=jMAuxT zdSYBU{~Y%G;x$8n1TEgpt(y?93?W$U*Uf`SlLcy-C(Qh>q;BMG2`)Q*rwepk1;rq< z#r==XfdbPHzkIv+i3BcSmGjx*{22qKvs)_?U4?aCIC&k&1MgL9=jzs3UnxjE=w9Xx z141(e&XDN8-eq2uGYQ8VrAJ_55>5A4=HR(igsDsi1YL%#0-^hPi(-|FH#JsaGnhLc z--B29E?91*Z}PQAhgbQ0h!$JGfZN|q*L`=$FCnqV(vF1AUf{ixl?nc@P&Kb5sM-w| zv6-zqc|*|>0v*5WqglbAb&srotU#h3bWy$aVP5J^8!g#z^20FTolLUc>rXvQmQe6o zeUS~hexLxMj$|Yd#m;NkFVxSC*+e{p{|q~(YN8M(#oLMQP;90|W6BTL515>WRU~$; zws?2PTXo5T1v?zy+z%00`Hu>O8#Tyz!nczpS9(fBk2@#fp=U!>$GQ7aug1#1O2|h$ zTNGxo{W-e}$!fY@X_*w49%|~$*toHnC6*pyPy{?myKF)8@zv!`4_DnoEq6gF2 zbY#Y+b!9_xeP);zjzl7XxZfsgprLWss|Hf%d}y1#D*!+AFFX4qhirv+LtjSywT;V| z^NQ;@IjIXp67X$W8Pe?FdvMtEv*FYGIxl;g|LP>*(_N8q?ob3XME#^`*>d>aMIsp1 zg4%80{RMvZP(F<3f=Xavl0v zOgSQgeEoC7iYf4L#1E>KFnpV?D3xrbIF=ZBMcs}R6H|;6FB_Cty%BNQ^`zd9N4$CR z69h|*q--R0A;40|*RDL}6m@er`?N}++e>T(uEPgjxZGRkp*aA=h3A4CU3|L(MgH+t z^|&{TfvHT^-T9Jq2Yd{jre(mAAn)sn3s_lxFJ?JR{~(n3&@^I8DGN-fbtZkmLm>0Y zktB98Zrkg4sqRP;tjss@P?6_#1oG8e-uM(+;5k<-w<~wIa=$%^AT%ksyuCBWN3vj? z+(A~P4C**!#jNY8x)*r=-Kp8-j=0>nO_td#O%2?M|&f98Rg5ZogSMZg!R*GF&PKJhCE+QHX$4^5_0zWuAkZ|C5RA1YO$BP-L@MzR$Ufa;45sn|v3m$Oe_NQL2dEI*1 zaa?J+grNc8OQmf!s13KCwB%LX98n--U#b01oe1awZx%Ns^W^@ycfwD1cOe=eX71Co zD%iPAXOv1`fv>qG0U<5^?YguBlr?UVFl=4#<+Tw^>98*s5pEg6FNF-r8~&P5v!}eG z2Teem4H|>9R}pvYJQUj+X+8TWmk~a)aP&7>@!iH>8@g0tV3K$`PZzk1{U$9bbiLtf zuP)N(+)aoJtPeZu-R~Om?EH_KBv{dNd{5cOE_<<2W0$u@>E!1F-{(T%vlb~cxtSw@ zxDyatyT?aBDDHVuXM>M4LPtj&v+jAa#36Tco;5xOR2tIa$#g}c*bNQAG&;AR=%5}|3Pr>?lTQx{cH2r}Pksv{~o;;qUWm(jnOC_lV z064(s631BTmJkEWPuF3*IzR~gzku?l7*KyGd!{>PHXKc7R^LLA2Zp4ku(UYd0$ z()&VV*PSs`vJ5;Y{mfu}#V~FVE$^2kL>i|dpr2UfFbcDQ5FKbeFL*eC;Pg4xK2#!a zxw(ZVTjjG7Oc;!nTsSBCqpP=}+!V58V65YLXlb%sG`dTi(&CK&I=tx(XQW zOl6}*%kNuQ#(KHYzj%n?v?Pvw01SJ<;=64vk3BwmnF<%|xc70I}Zn3SCbCPBb$LDpk^ReB#FQ-tX^!SKkfM3EJ6qK8J;YvC%+dKIA0AT^*G9`1Ux&HV8v3S)i>UY3EKzQ5mN%XFn{0O|y1O5A#C0`jdi|m#W zWKU3tJAdMALR!wkW&120;vA+Sr}*N2&eaW_oUzOS$pr1~xb!u&*0Z^@0!UD<-hx^Y zJ=YEWPKXWJ_XP)0{Mv5x5UHmy?o@%+Ffbak*6UaTaT?58nGbxCIq(byJ&h^^)f53? za@%E>rkwGKf$2ov_b4qIRG#z+G9FfN4pyc&n(D38nxLA@;QfKagykAx66j4IgiU`K z(OkPzWF@!FVbe7U1Q_~%>LM9D)5!3{fL&_!6!0X+`c7hxrWI3nFM^@-|4&;a%~P5_ zRWwJ&R}k5W(i~+MM4}}sj0WI}&N}IzND7K!QM0>CM@`_{XL*lCGcMZDx~jaZ(Z5d= zwfsgD^7(my(FlCeElY2J^x}+0jQ@brE*T*kfC%1TYSBWb(PhLrafdY)&AGoB& z#weXwwaiD7oaaCb9Fpx`4H&;CerHEBJ#Ls8}}ejJV3}2!KeB?c7CJ5ZD5xsO|ph2)pS; zMxSC!S*wYbSL`gZI6EM!0u{Eqne4Cw%d&7=dGQZu???Mn^mzRZ^027yKT7ZR#{9YHL|79^n0yP>F77=xF zdJR3wi zc&)&~dzddyhzOp*#N#b9ewhEb7xO{nD5UFS2Li>>2S$P!u*q_`5vCqMiRqumSPy9; z5u(0*-DG`cfvZ-d-o3-Pf?wX}kC=NdxQ&e>0o=j4NO2=rQ7o7DHwm*Fz^aJ(^kmjmTp1Q%fTq5rQ!gxu+O)?egjh(2vZ8e9xzW9pOziNr0@ zgqeZL%((LZsjz7wo95dBj**Ssi+bqqJzrNhaq#&HNor;>P<=HRB^yHnGqKs|e5szN ziXaj;>CZZTGe$Ft270QBCSqU;t2_--MbSplSTXBX` zQMxIv+61KgAy$ZKa_h~YIfL6o_dcN%ko?Ckb~}`R5gA?N9$jZ~YEY!HN|nG!dW1RQ zEv}`l(9PaaId3uop{TSUQ!rq=+&XTLB>^7+St}?Xcbt91z@$H$;FKY0_QRQil6%#& zu&ND$fYA}K_XvYWA%q>_g&OTgK0>^m`**Q$Z)R!`%e2Y3Zzjn&)c-vg?Xk?}rN7*a za9s8qGXTnvI+1yEr`IUJH$lw>vja#JH_-Hc)r_FlRrkE7QqDxj&9nIas|9g1dA*tW z0)SV!$HFf#oxPDYhc!;aM;;*(3iBPheaqBCi?)e3f3KKlPUG(Y594Pu92m+#8U}bJ zAp0eZI8HXKQte$(B-I$%x8WsZqeCv{HcBeh&6f2BT!)g6Ik@7`us@m!hGXDMrCyrCl&-1I@t>n?ArYp5cCsK{X~2N&4) z6TQj6VzVyx?cT;kA)FLF6ezUT@A}HFHzf>zH}3B7suC> zlA!xja!(dls9GI{aX%Y0k6A&RH}zd7SZTURFu_0ty9{c5DQHOgGU!i11uwl%H;>c{ zpLS0@8~iW@iRg;TnL;qvkJ$(05;*+G_7!T1Z_}_OyFlfl}Je)4gZ+;@KU&=z2@-#dtYn91J*2|Omj^lPoPzr+^NK>tg z`z-j0&T7xFI&H!-y`sm0$4BiNPO~T~9;UtE8h(4G`?9I{TXfi@*>*@k~C<7R7yVOki$1cmvQ5(If zB6re~w>avM>hZLxoK`ti0&Z@$3oeQiD_hR)g|foOpP()?IE16)eR#y#C%O%dj8)pV zDBRNPCVIzX<$|a`dvbd&SbnVK#M^2cik=5bYt+nJ%=zOkf5_VYJ9sRK>@USt-J}Wa z6?{CH^srHNzw5BW6i@9PHZK)nI01;nNLsOZ%v)^Ti2ke7d_{nq#iJR1Vvp>&_TNLA7Bgc%ILGvgI*Y9?&NGE`vd15w~Q%%defX-I57(Au4FR%F9 zyheNW8U)%x8Y)!JS&NKWU$Y+$6uU9q3JPyAsUNJy_( z;bCbiYC@|&``Z5<;YtJS__6eb{)r(CGCI6kyzdztd1v%b1j^vB@`p6NkV^er4aUweUaoQ+WIB!B4KEY3`%8AO4Q;6W~59vT!%IY7N zHtAI>7OPUSt#GRR(x`!9tF3!HI3r_#x6%;mLFoeeESl;~xK6L$js|V9N+sxQPn~_ju zu94oM0J$jWskj%Va}Ew$fH>`w=<8s1p&e4y&E!rZe#ODNRY>wr@uDVOfRVcSe6Yqo z0%by-lztantg4H-PT%X{c0|cvY4|2ILR)>BEKtX9T=?pv-It1B7Pk`f6MS@9KoXIx z{Gq2B!jM(adHSC7hOjp#k7(PAJMQDyc?6a3)D@*0AsOYHQNHzy8KUc5CpwxR3-ongXX9LHzn0>JbIwNBI-Z*n) zISBc=weqEzA=QzH+IUgH9M=jBWZ}@y@Hdh=>K2Z!r7Aoz21F`w=V_X-Na- zkmTn@0-ms`ZoaQZ!QV5%fguf{>#l8oTj|*;r4SQEQj|A~C>?%Y-AgGTOjfBaqgHA$ zqsjN?L!#U%fJvw!1D0d;CAc)~Y9=9|56cew8${2vsrFYm>%vq=fbv=OsBWcluK>6Y zhRXb4%RJ2rLPmXHFI5u}%nq3(V^0RC%CVX88l!QLweS-@j0x?b_&qG$9AImYXJ{M9 zb(FiKj^oxgtTg0E;!k`E-PFvEagqdBh$^+;mQP5`G`~qo=axU!0OCZ@k17=O`hySH z%^AbXFQm~snnIDzsl|9o?iJ2S>?A`2Y=BfbS}^13f$|w#`y3t`5TK%qu+nsrlLxcs z>VDDN0$_HCi=zdmcVb^?O$TN1i%df9l7}}SgB5#&NE^?U#Ev`bY@baKDnb>=?+ceB zrSz|U1)#8ePdIrF&B%r0TSgGPyNnv057kR!T!rVyep4w1ER^|VfpZuc?`9-Lqw0Ur z1cNLH&hqQYE#vJa!Zcz84alIq%+w(Hws=An_(u99S>@XEqKV9cY9ZBRfiK8E0f|W> z)LJ|WYg)z-GgDP0JwZ;0p5)TD55VP$`Bu2cvchSUJh+5y^eL&E3Q7ekJS;lN^>g#N z5y)D0Dq#m7mg2$tX^v!HjFf75ZM@i^a+>tg3C z;GWDmQC%zW-jxU>79GxW0xt8ALK+f8dkB1Z(z$6EdUgac@nLV261Ut2)e=*oHGLS1 zePdD-UE|=LW1&d*l+NIZHG@9rNXi#NAa#6#t3mo(D{nin37Wb@3WwXOSyaWPs4BI^ zUBV6X&F!on&Qfkrfyo@3k4WxJIjB|Pn4U8w2$rU?gcrzW5am@>g6 zd7EKrx{4X5RsuYA7W$=V_g2>lz8^;&zlbmiuD?EOMvPkF+2GBLCK8n@;VJ`V>a5yD5 z2o&(ax+dYV2JtB9@K*0Jo1Ct`$o=Ftda?wr%`s(2a+#kM&(E%}Qfh;hx$r7GcoM); zPk9^~1F>2W$1?(gN$6W+tIDv7=p+C`IDNvjy{$kkpZqD1f_)4~W2Tp^9XZd|9aT*K zprMPEK|)3kM6aE&!e>QEizvocHudnZtu;s(Bi{*lVAP7_0hQx#yO3N~VR~@gCf~AH zpEFq>ORa~1<2s^SZ_t{fj;8(<2+Q*D@)oseB>) z3V7Cx(*9KjG%5PR6cG#1vFu*Ee@{s4XzA2eZ-GuRHhEOLjH3QkxR35t$-%M@x6}zTQe$ zp?6Bs^Hm;64XcAt?l1ABA9GjW=QN+6C!9U|U{$UcX6m|(&2WW$rEj$bMsD%p^*PmaDAZD|m*Q+{G9?l}7F(`vX zLIg}WzFgy7w8L@;2z*L?Ruyt5IfFlwnrQ0Jw5{tRT0V&CeUUeiLN4ULM?@k3hF8z0 zK~PMMG0bJm>Go!rq? zJ2nzEj1!20^a)pytfv$D_5DkVa}xI2U5i3%Js6R=G1Vi0I=(*p8zgJypbF{0Vo=Z9 zLIa|yI-y|?9HeW)p$gNltTI~6qf^}!af}P?zexQB2}y0J>^(q|$B)HJFg&$FiP!0s zQVU1q7e}Krd+*%XxG&9!4oouPhjdXzFi&c)z?D=k}HsQJ43FyQ>u|3L`K_(C2S%EEADgs_M_wh$wqf+i_@Vt?-VB>3^r}j@# zxe~fxpuF5^?A_L7zl8sg+)e#viwFwLkVkt;6v$twRXhlfUvwgV}BQSe^F`2 zPyHX%?+Ju|4|*9+ujgSpRjjAIGIwMukLf3FcUrYjV5IYoxvKyt-UI}Ji ztXU}X?xABn2Gyk@_WUCdn8HD60h9@-l=!3&W;qXaxFuY!I`)v9g%X1cMN82Z^3Y1lMAhmGR~U<5 zi4a<7w_fa*CuIcna56>S!x&6o0>=h@*`dVc*Qu-B<#JF0jn>6 z%;*8YK_0De)8U}dUQZW9(Y)DL?IAlsLJj@-OqH~I>Px&bdgIVvGh*L70=Jw{fpUC4 z%f1HeA1sP`N$KXsHhzAR=gHOrr-6lb;U1_nBWyV9sOpIehwYK`n*qvF(1Jtq-*}nq z)U`+jMZv~S1=`~1W`xM^X^2quOHE29f(;EaUOb%D2`a$@Zb(qezls6wC}du|G((kX zL)mzW?w&MWTOb* zL&^7ni~semF)K|7O_PSQ8qJawYW(7Vs-m^$WfPgI22?Te0!zsGSD&x1;wDl(1MWToara+wdLf#uH zN=_WjRyR>YZfU{|n`VR3XQb7Nc&P#d$od>P6}p6uPB?a%7)%|Y&dK{B*Chf1ndZ)~ z_U_0`NIboh{@?<#QLvD54@?gZxk`fzpOhuJ(h&%Q8xtg5KLtEM2N<#@xAs)(N~m8e zc7vmis6G}X%&-mk+5L|JNHv(A zDo`c*AAdx9@&G`IyblsDWh$=-VsB36YoATw=~kT>T5Zt<|Mk)pPQ72rh8zE2u1G4- zSi!QRCXNL~#Y*V;uxY$FGmfsynbrL|)cS0okC5`6WYrO_kbf%14J4q;T7NfGD&Ad0 zwlmfPn9jP~>DmrWA(pv=)58M61*_E3VL(;DL06`bbTNFn_-tyRu{$jNLDD^Y@`)G>y9X5^`rvjNCPcItQw1DeO)Sy~Y&pLsdH zy#uv(6(A`>SS(7CZoB0+>=i;Hs~sUM?X3u!xQC8fERI{ZeZR@HU=Gaocy(FV* zI1F%LR;sfa|AM$mkR%YEr3A^<17L5=cLL(raolw)apB^ajP6swsEy_XLugkn7vS)g5s3$A^+L^zhVr_&5@~ z?eCBL z$9%wePIBy1*@dgHQqqL%PKW`LlPUz=R(N2GL<0O#{%;X)97B?96t=rpEQUNT_*b6P zN$LIs|AP4pB%MwDe>n4e7y!^a9lO{a%7Y&;K$q~2sQ5R#-0yX>SZ!*vADmXoYK^Z= zs&v0F!ZERW6v`6_T=}x9Z$;PI$ya*X16lwB7GEJ?TG|UQTPfj@J}_4Mo!Jkbm^WmA z^Z;gaH=S=j2`31T*Plf`pTd0~sK;4FlM-pJ%^K0E$GOc3@3{)74e~HxfmU1OUGMvr zF*iFlG1p&46e;B4WA)v-TRbys?-Qu7^~V96FAHLEYZQ9hB}d``*CqCCYM|N9Fi6Vx z%$Wg=npZ9~s{5Zv-=e)mH?vkqLx`N83m!?>F{M?XdlSJ5i+W}k$@4unUiaTXuYE@L zFP1A1dQ;DUWeAsLBzRRgO@>Hw;h0L>T^d8!r%k(wrP>RP@(=k{^RN_vIU&u|PpJq` z_&{hqIW%ddcS-?Q?+TBp`7d9ECf&{!&7l~1atLO0>zzmxy5V;ci2yK1$bj_v+pw}5( zz&6SkQdSIM@A)%Y_*o5PX&MR7_)^sP3^Q2wKWHqe7%&a1>8cgs`-%X{1+k-mUjCKV zJn`B3q~r=LdkOvM+b)KTPla|b4Mj2s?NWv%k~)+Eni&2xmSyP)Nd0i?Lopo@DSTtMoAzI0XTPU&H0_e$ju z2KNwRlpiv8BI}o?6$~rP7*c=T!C?Yv>f{~#dP8{!40;@AG2;jgYEVj_^)**}>t-MX z8Vu^C;wt7*fbj`N2cZcr`~3BEo}R1kMWui<_fiKM;{KR=;S>xs42OwVc#M+L+sNzh zaYQJALjqKyVuyz5g|O!DCooTNg&fl%gZZ%@@8c~v9WKltk3@JY10V0=sv2W+_W0tUSa951PY4OdTIhDx&2&W#2llT$ zOSRoO&Fzvntulc^Bj9ch6rca&E9+6ZjK4&-HwusbU*`E?`YhJLr)Q;mx7CqAp~7H( zz~Lzd=CV4`RR*HB8xfjPw-g~Sl-sv!N4HiBjS9UGMbsBhDxWX}Jp+Ln;mCe)w>t8! zKRi_X#zVr-v(KS%%fB(v#Jmi=X+RMt;Zq=>!TzZVMv^|YAP`=H&f++|&o!&ZO&z6Q zeTOe58E(+^KM`NMNCXrb$whELcR|2`9vTvv2@jbOC#6`T?WoHd&DhUa7YZFy1ftCy zY#tUMFIfHMefVD(5)&loz-5_9X)gq%bxqk4HQ$3SVSDm-_9moU{C3)Bq@e#Yt4i8A zH5IR{LNNXjJ~JD*L%+SLu~O4v8v7mz-`G3^ziJP%yrDRB(Tx@SaNP>EEOqxg!SmK^;J=bo3@1C8x}$`AJf}HmRKW z;AX%S{wSRWO}{jwYJ!QEYecYck5f*u55R=+oHEK*l=Z$Y8&u@+SC&FlU3fa_EoRY) zZi-xh-h9kig_9D=sEvn#OgM=PKUe1gITu}5{ENM=s-y3;M-6|IpFEYaWaH3Za`V2G zy(MUbgEYPoa&4lZTpv`G!kV{!#eVTb11j*V+&oGn^;5(DwRf#wXbW2(dwJnn_GFLc|0_ z1Z;hfa3khrkcwiWhykB~ASy7YvpVx({($+E`}I8TZ|~pP``mlZJ?oaWoEtclx#!=T zPSEC|P|$bmpDnVjjl|zI)~^PE6KRdpOJIHSw|8%_khB9VB!R7z{cpI}|Kq9#V72yD zXFc)W@}1vvDL8}OtsKNOA^*b53-}Xq^XZcpd&Kv+j+-$i_p1Sf;ipsgFp+Wm(>uZ* zhUPPF%OL2L!ymo>?h((P(N~b|8GqeE>OZwd*88MC^T6h=P3-wz=QC*P*Q{+^7&84+U&&!(Y{F~}0>*dv{_w;b+o7s*PVd{f|- zQ&|oX(fTFif8GpXt!>Crxzi^rqiM{o#yPjGTDvjUp9T&`pfm|Ox1-l)V=#+zU7wL?cf?I-`17U=hRfb5bv>hE(~}(> zQkidDL0M3-N@Cn9;d6t`ZtWDuQ_oLw8g2;Y<@i(-eNlu{idssH<^uNtaZEw7U+ml6 z<(H$o6G#rt+HiGdQ|ZJ}=Cc7--p}^d3zk~4hAS5)ae0mBNXCWlEK{<1m@AZ>NKQL~ zK)nyhGjBs^c;T-G*U;4+2eB)H{NpTDvaJ5qg2Vb{L1!s=L^S*O8y-;-GsBhFuG-kGEW!0Hc z;ZZR%y+fGKoN@+<7R3*(j=4cCp;HL1OD)=^9-U(ooVQ@{!P%RA0>9d3(w~du5DKRk zDmfv9`N8|ssgIYM@oFyH6b55fMJ;;HM5n^!p)&1#aR0_#-GT!_<0r23rgXs=4AyQl z)c9PetzYShv#hM@96wW}(|dGBSHuPKr|~+G$p~A&sqvY4V+c{D7S%;6{)o-@Zp?wP zVQ_-JV4&0Ui8zLmo<8wRM~Y>fAmPts8@i~(yy7wv7zziai+r5zQb<HbnHy&K&8F$nIwk?mBu4uR+C?c2k@(s%o->7JVqiRiW5yi1ROU#J?E6=su ziCQTUKT3xCT}_#U{}IUg;qL$o^-g}HNiRZU^W9A5gZbDnat~6Nq#Y5>Cc}B-UxVmw zN&hR5jW<#O+xr44tTsb^eerCn)$QHG`J5#rYn?%NxDWkz!|l6d>Uu(}B~<6QNx>|i zgJj7CWtZ}o`j|h_<_G-PYkdsktbvPf!FLG=oE@nN(VTP)i&j{>YLE!DhQ`opMMiQ1 z8Br)TLwiqp-)6!LpmF;O&RCwP@zPaT?EwC^7>R~Gd$S17ss;ZMNJQG-50xPRpw^`a zU6Vd6z=BI?98%s4;XJ*hw2CcN8L$=|5MVexYODeoyF+D-iHK_*P#j<`g*~^)Wz=Rg zc?RR>Zd(jVcSf~J8zBck3QOT435B&XAxV3oefFb(065&|d3 zrUJv_T#G;%lA5+)hBeq7GW8iliuUB3hI=@S$PIU{KmTi1E$ulPkpC*VYo6ihZLpDT zW)p=WWt05b5hH2hHsZon$OghGrnwz_28p5qxYydU$R&%CSd2`~6Q*blcf?t{;h#c$ z&tHq~zK^v&@HgK3d`5pu*)e~&vZ0P-R0KR8u=r=e>0!xS)6udvz(~2*Ly|75?+!@- zTZ~M2jLtI}SJ!>}NznM~fu;9brBh$rwd)23e)EjAVQ2zm`8DrS@YDnHAdW0AB;ikI zCyoJY*gXEXi_zU}9rMiKK^D2;U{%R6l29I!nlP$t>&j0otEej+8UmF7LaAXjtX}JK8n-@)C*%ku;4lEsI9{_3rw6DbXlp9zf?1uzFtD^s zr+ReOVc^^PmlobS5;Q)nXY{u+Ee3VYV+mD27_AFk)sVP!#|uU0oBeXXEj7}nq`}b` z*-%!5b|8^5vXN)}QMJD4^%hXL@|0n0;`~8&pQNP~vjGaajczVX9wesV_$o z2E*u+Qw8$51}gKBhk{85NR*&-MrPo1Jhb);B_;G2yOesZJ%VdX+_Z2T7{PhAmFeWK zdBR2UC5!3;_b8S1SQJ=vylih3XgRmH6o;01CUN#T_I&49?)Fp^<5+UTVFcXUoO1vTncEJ~^j`DJ4a_O-bF&Qe1XMJqLn`2$&PJzjD^Wq?n?cSO zm)khCNWJ|kZu?xZwzKrD5k+abZut~codldl#Wu@9Q^G)Iuk%XRoVt&3y z#J?2@ahgHEoy8NLwO%~zGyU*_WvZ!t_FIZ{;XYzH9CR#+l*ck3;?+JA0!FLFw|(|n z0Nj7rXTb|-SSwxIdx+-I@N@U(q-ZU313-*v5otukawQlorS2a58Me|MnfD(1I4Kg} z7|PP5acv2H-CCf|_0y4EJDa*D-bpxzCP@Xs17ccASj@sQv_@(6;lEg+G$HfMsc3jZ zu3?jfrq7K6>B&t7c$E7J%CX7u3sJX z?qbezqGD7tz)NWQhHP|Fn0$H(qT;qe zdx3g3*eZpqc~&;wbw03OCdB9WZE|M8JCR{<9cx`~K8P<$qRiQ^Sj3ah2Fbiv;s`_* zL;R>NfR_gRAy5wPaKJm`&)(ruaBRIZy;+9E77MR^*5&I@T4`q;SeI>`ZlkJtgquczE{c?3tTC49gb#+fg73_T{J%4 zz6(+T!}{9sEV$HmW_!pyXGo&xu$o3af|CMQu2?>8B`A;6psG~B*1WUSj8vQsO=Jyu z=#8>S&UNKVAG%~QTw+)jBxZ~#+&r>}5Ang19_mGBj$*dH@wQl=$R-+AFQdnJ_*>5F zZsZ(31_}Y(`+n%v2$i;Gna#v6p7U%RWamQ(|1?AXKM2z}?oEx$Zme?->#mOR*h6C7 z%&hvrvMsIAPKPf}mraW(azC)E7E0cwXf>FV6?VbCEoE khUa$pe46`=0@p_$B)l(p@7Ndr0x94;>Hq)$ literal 0 HcmV?d00001 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_map.yaml b/gym/f110_gym/maps/Spielberg/Spielberg_map.yaml new file mode 100644 index 00000000..23975772 --- /dev/null +++ b/gym/f110_gym/maps/Spielberg/Spielberg_map.yaml @@ -0,0 +1,6 @@ +image: Spielberg_map.png +resolution: 0.05796 +origin: [-84.85359914210505,-36.30299725862132, 0.000000] +negate: 0 +occupied_thresh: 0.45 +free_thresh: 0.196 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv b/gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv new file mode 100644 index 00000000..5e8f9232 --- /dev/null +++ b/gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv @@ -0,0 +1,1695 @@ +# 17b4de0d-c737-4d0b-b937-32bd2ef0c95b +# 603fd3987364b09f9aacb70d1ed12c268e24dd56 +# s_m; x_m; y_m; psi_rad; kappa_radpm; vx_mps; ax_mps2 +0.0000000;-0.0440806;-0.8491629;3.4034118;0.0000525;8.0000000;0.0000000 +0.1999592;-0.2372250;-0.9009210;3.4034229;0.0000585;8.0000000;0.0000000 +0.3999183;-0.4303688;-0.9526814;3.4034352;0.0000644;8.0000000;0.0000000 +0.5998775;-0.6235119;-1.0044443;3.4034487;0.0000702;8.0000000;0.0000000 +0.7998367;-0.8166543;-1.0562099;3.4034633;0.0000759;8.0000000;0.0000000 +0.9997958;-1.0097960;-1.1079784;3.4034790;0.0000816;8.0000000;0.0000000 +1.1997550;-1.2029368;-1.1597500;3.4034959;0.0000870;8.0000000;0.0000000 +1.3997142;-1.3960767;-1.2115250;3.4035138;0.0000925;8.0000000;0.0000000 +1.5996733;-1.5892156;-1.2633036;3.4035329;0.0000978;8.0000000;0.0000000 +1.7996325;-1.7823535;-1.3150860;3.4035529;0.0001029;8.0000000;0.0000000 +1.9995916;-1.9754904;-1.3668723;3.4035740;0.0001081;8.0000000;0.0000000 +2.1995508;-2.1686261;-1.4186628;3.4035961;0.0001130;8.0000000;0.0000000 +2.3995100;-2.3617606;-1.4704577;3.4036192;0.0001179;8.0000000;0.0000000 +2.5994691;-2.5548940;-1.5222571;3.4036432;0.0001226;8.0000000;0.0000000 +2.7994283;-2.7480260;-1.5740613;3.4036682;0.0001271;8.0000000;0.0000000 +2.9993875;-2.9411568;-1.6258704;3.4036941;0.0001316;8.0000000;0.0000000 +3.1993466;-3.1342862;-1.6776845;3.4037208;0.0001358;8.0000000;0.0000000 +3.3993058;-3.3274142;-1.7295039;3.4037484;0.0001400;8.0000000;0.0000000 +3.5992650;-3.5205407;-1.7813287;3.4037768;0.0001440;8.0000000;0.0000000 +3.7992241;-3.7136658;-1.8331591;3.4038059;0.0001478;8.0000000;0.0000000 +3.9991833;-3.9067893;-1.8849951;3.4038359;0.0001515;8.0000000;0.0000000 +4.1991425;-4.0999112;-1.9368370;3.4038665;0.0001549;8.0000000;0.0000000 +4.3991016;-4.2930315;-1.9886849;3.4038978;0.0001583;8.0000000;0.0000000 +4.5990608;-4.4861502;-2.0405389;3.4039298;0.0001615;8.0000000;0.0000000 +4.7990200;-4.6792673;-2.0923992;3.4039624;0.0001645;8.0000000;0.0000000 +4.9989791;-4.8723826;-2.1442658;3.4039956;0.0001674;8.0000000;0.0000000 +5.1989383;-5.0654961;-2.1961388;3.4040293;0.0001700;8.0000000;0.0000000 +5.3988975;-5.2586080;-2.2480185;3.4040636;0.0001725;8.0000000;0.0000000 +5.5988566;-5.4517180;-2.2999048;3.4040983;0.0001748;8.0000000;0.0000000 +5.7988158;-5.6448262;-2.3517978;3.4041335;0.0001769;8.0000000;0.0000000 +5.9987749;-5.8379326;-2.4036977;3.4041691;0.0001790;8.0000000;0.0000000 +6.1987341;-6.0310371;-2.4556044;3.4042050;0.0001807;8.0000000;0.0000000 +6.3986933;-6.2241397;-2.5075182;3.4042413;0.0001823;8.0000000;0.0000000 +6.5986524;-6.4172405;-2.5594390;3.4042780;0.0001837;8.0000000;0.0000000 +6.7986116;-6.6103393;-2.6113669;3.4043148;0.0001850;8.0000000;0.0000000 +6.9985708;-6.8034362;-2.6633019;3.4043519;0.0001861;8.0000000;0.0000000 +7.1985299;-6.9965312;-2.7152441;3.4043892;0.0001869;8.0000000;0.0000000 +7.3984891;-7.1896243;-2.7671936;3.4044267;0.0001876;8.0000000;0.0000000 +7.5984483;-7.3827154;-2.8191502;3.4044642;0.0001882;8.0000000;0.0000000 +7.7984074;-7.5758045;-2.8711142;3.4045019;0.0001885;8.0000000;0.0000000 +7.9983666;-7.7688917;-2.9230854;3.4045396;0.0001887;8.0000000;0.0000000 +8.1983258;-7.9619769;-2.9750639;3.4045773;0.0001886;8.0000000;0.0000000 +8.3982849;-8.1550602;-3.0270497;3.4046150;0.0001885;8.0000000;0.0000000 +8.5982441;-8.3481415;-3.0790427;3.4046527;0.0001881;8.0000000;0.0000000 +8.7982033;-8.5412208;-3.1310431;3.4046903;0.0001875;8.0000000;0.0000000 +8.9981624;-8.7342982;-3.1830506;3.4047277;0.0001869;8.0000000;0.0000000 +9.1981216;-8.9273737;-3.2350654;3.4047650;0.0001859;8.0000000;0.0000000 +9.3980808;-9.1204472;-3.2870874;3.4048021;0.0001849;8.0000000;0.0000000 +9.5980399;-9.3135188;-3.3391165;3.4048389;0.0001837;8.0000000;0.0000000 +9.7979991;-9.5065885;-3.3911526;3.4048755;0.0001823;8.0000000;0.0000000 +9.9979582;-9.6996563;-3.4431959;3.4049118;0.0001809;8.0000000;0.0000000 +10.1979174;-9.8927222;-3.4952461;3.4049478;0.0001791;8.0000000;0.0000000 +10.3978766;-10.0857862;-3.5473032;3.4049835;0.0001773;8.0000000;0.0000000 +10.5978357;-10.2788484;-3.5993672;3.4050187;0.0001753;8.0000000;0.0000000 +10.7977949;-10.4719088;-3.6514379;3.4050535;0.0001731;8.0000000;0.0000000 +10.9977541;-10.6649673;-3.7035153;3.4050879;0.0001709;8.0000000;0.0000000 +11.1977132;-10.8580241;-3.7555993;3.4051218;0.0001683;8.0000000;0.0000000 +11.3976724;-11.0510792;-3.8076898;3.4051552;0.0001658;8.0000000;0.0000000 +11.5976316;-11.2441325;-3.8597867;3.4051881;0.0001630;8.0000000;0.0000000 +11.7975907;-11.4371841;-3.9118899;3.4052204;0.0001601;8.0000000;0.0000000 +11.9975499;-11.6302340;-3.9639993;3.4052522;0.0001572;8.0000000;0.0000000 +12.1975091;-11.8232824;-4.0161147;3.4052833;0.0001539;8.0000000;0.0000000 +12.3974682;-12.0163290;-4.0682361;3.4053137;0.0001507;8.0000000;0.0000000 +12.5974274;-12.2093742;-4.1203633;3.4053435;0.0001473;8.0000000;0.0000000 +12.7973866;-12.4024178;-4.1724962;3.4053726;0.0001437;8.0000000;0.0000000 +12.9973457;-12.5954599;-4.2246346;3.4054010;0.0001401;8.0000000;0.0000000 +13.1973049;-12.7885005;-4.2767785;3.4054286;0.0001362;8.0000000;0.0000000 +13.3972641;-12.9815397;-4.3289276;3.4054554;0.0001324;8.0000000;0.0000000 +13.5972232;-13.1745776;-4.3810818;3.4054815;0.0001284;8.0000000;0.0000000 +13.7971824;-13.3676141;-4.4332409;3.4055068;0.0001242;8.0000000;0.0000000 +13.9971415;-13.5606493;-4.4854049;3.4055312;0.0001200;8.0000000;0.0000000 +14.1971007;-13.7536832;-4.5375735;3.4055548;0.0001156;8.0000000;0.0000000 +14.3970599;-13.9467160;-4.5897465;3.4055774;0.0001112;8.0000000;0.0000000 +14.5970190;-14.1397476;-4.6419238;3.4055992;0.0001067;8.0000000;0.0000000 +14.7969782;-14.3327780;-4.6941053;3.4056201;0.0001020;8.0000000;0.0000000 +14.9969374;-14.5258074;-4.7462907;3.4056400;0.0000973;8.0000000;0.0000000 +15.1968965;-14.7188358;-4.7984799;3.4056590;0.0000924;8.0000000;0.0000000 +15.3968557;-14.9118633;-4.8506726;3.4056770;0.0000875;8.0000000;0.0000000 +15.5968149;-15.1048898;-4.9028687;3.4056940;0.0000825;8.0000000;0.0000000 +15.7967740;-15.2979154;-4.9550679;3.4057100;0.0000774;8.0000000;0.0000000 +15.9967332;-15.4909403;-5.0072702;3.4057249;0.0000722;8.0000000;0.0000000 +16.1966924;-15.6839644;-5.0594753;3.4057388;0.0000669;8.0000000;0.0000000 +16.3966515;-15.8769878;-5.1116829;3.4057517;0.0000616;8.0000000;0.0000000 +16.5966107;-16.0700105;-5.1638929;3.4057635;0.0000562;8.0000000;0.0000000 +16.7965699;-16.2630327;-5.2161051;3.4057741;0.0000506;8.0000000;0.0000000 +16.9965290;-16.4560543;-5.2683192;3.4057837;0.0000451;8.0000000;0.0000000 +17.1964882;-16.6490755;-5.3205351;3.4057922;0.0000394;8.0000000;0.0000000 +17.3964474;-16.8420962;-5.3727525;3.4057995;0.0000337;8.0000000;0.0000000 +17.5964065;-17.0351166;-5.4249712;3.4058056;0.0000279;8.0000000;0.0000000 +17.7963657;-17.2281368;-5.4771909;3.4058106;0.0000221;8.0000000;0.0000000 +17.9963248;-17.4211566;-5.5294116;3.4058145;0.0000162;8.0000000;0.0000000 +18.1962840;-17.6141764;-5.5816328;3.4058171;0.0000102;8.0000000;0.0000000 +18.3962432;-17.8071959;-5.6338544;3.4058185;0.0000041;8.0000000;0.0000000 +18.5962023;-18.0002155;-5.6860762;3.4058187;-0.0000020;8.0000000;0.0000000 +18.7961615;-18.1932351;-5.7382980;3.4058177;-0.0000081;8.0000000;0.0000000 +18.9961207;-18.3862547;-5.7905194;3.4058155;-0.0000143;8.0000000;0.0000000 +19.1960798;-18.5792746;-5.8427402;3.4058120;-0.0000206;8.0000000;0.0000000 +19.3960390;-18.7722946;-5.8949603;3.4058073;-0.0000269;8.0000000;0.0000000 +19.5959982;-18.9653149;-5.9471793;3.4058013;-0.0000333;8.0000000;0.0000000 +19.7959573;-19.1583356;-5.9993970;3.4057940;-0.0000397;8.0000000;0.0000000 +19.9959165;-19.3513566;-6.0516132;3.4057854;-0.0000462;8.0000000;0.0000000 +20.1958757;-19.5443782;-6.1038277;3.4057755;-0.0000526;8.0000000;0.0000000 +20.3958348;-19.7374003;-6.1560401;3.4057643;-0.0000590;8.0000000;0.0000000 +20.5957940;-19.9304230;-6.2082502;3.4057519;-0.0000657;8.0000000;0.0000000 +20.7957532;-20.1234465;-6.2604578;3.4057381;-0.0000725;8.0000000;0.0000000 +20.9957123;-20.3164706;-6.3126625;3.4057229;-0.0000793;8.0000000;0.0000000 +21.1956715;-20.5094956;-6.3648643;3.4057063;-0.0000860;8.0000000;0.0000000 +21.3956307;-20.7025215;-6.4170627;3.4056885;-0.0000927;8.0000000;0.0000000 +21.5955898;-20.8955483;-6.4692575;3.4056693;-0.0000990;8.0000000;0.0000000 +21.7955490;-21.0885762;-6.5214485;3.4056489;-0.0001051;8.0000000;0.0000000 +21.9955081;-21.2816052;-6.5736354;3.4056273;-0.0001108;8.0000000;0.0000000 +22.1954673;-21.4746353;-6.6258181;3.4056048;-0.0001138;8.0000000;0.0000000 +22.3954265;-21.6676667;-6.6779964;3.4055818;-0.0001167;8.0000000;0.0000000 +22.5953856;-21.8606992;-6.7301702;3.4055582;-0.0001180;8.0000000;0.0000000 +22.7953448;-22.0537330;-6.7823394;3.4055346;-0.0001181;8.0000000;0.0000000 +22.9953040;-22.2467680;-6.8345041;3.4055110;-0.0001180;8.0000000;0.0000000 +23.1952631;-22.4398042;-6.8866642;3.4054876;-0.0001155;8.0000000;0.0000000 +23.3952223;-22.6328417;-6.9388199;3.4054648;-0.0001131;8.0000000;0.0000000 +23.5951815;-22.8258803;-6.9909712;3.4054425;-0.0001091;8.0000000;0.0000000 +23.7951406;-23.0189200;-7.0431183;3.4054212;-0.0001041;8.0000000;0.0000000 +23.9950998;-23.2119609;-7.0952614;3.4054009;-0.0000989;8.0000000;0.0000000 +24.1950590;-23.4050027;-7.1474007;3.4053818;-0.0000915;8.0000000;0.0000000 +24.3950181;-23.5980455;-7.1995364;3.4053643;-0.0000842;8.0000000;0.0000000 +24.5949773;-23.7910892;-7.2516689;3.4053483;-0.0000754;8.0000000;0.0000000 +24.7949365;-23.9841337;-7.3037985;3.4053342;-0.0000656;8.0000000;0.0000000 +24.9948956;-24.1771789;-7.3559256;3.4053220;-0.0000552;8.0000000;0.0000000 +25.1948548;-24.3702246;-7.4080505;3.4053126;-0.0000389;8.0000000;0.0000000 +25.3948140;-24.5632708;-7.4601740;3.4053065;-0.0000226;8.0000000;0.0000000 +25.5947731;-24.7563171;-7.5122966;3.4053042;0.0000032;8.0000000;0.0000000 +25.7947323;-24.9493634;-7.5644193;3.4053080;0.0000352;8.0000000;0.0000000 +25.9946914;-25.1424095;-7.6165435;3.4053179;0.0000305;8.0000000;0.0000000 +26.1946506;-25.3354557;-7.6686671;3.4052921;-0.0002878;8.0000000;0.0000000 +26.3946098;-25.5285048;-7.7207797;3.4052028;-0.0006062;8.0000000;0.0000000 +26.5945689;-25.7215579;-7.7728659;3.4049954;-0.0018200;8.0000000;0.0000000 +26.7945281;-25.9146310;-7.8248816;3.4044521;-0.0036145;8.0000000;0.0000000 +26.9944873;-26.1077465;-7.8767590;3.4035492;-0.0054763;8.0000000;0.0000000 +27.1944464;-26.3009068;-7.9284187;3.4022122;-0.0078970;8.0000000;0.0000000 +27.3944056;-26.4941633;-7.9797772;3.4003912;-0.0103164;8.0000000;0.0000000 +27.5943648;-26.6875186;-8.0307333;3.3980418;-0.0134694;8.0000000;0.0000000 +27.7943239;-26.8810112;-8.0811682;3.3949863;-0.0170916;8.0000000;0.0000000 +27.9942831;-27.0746851;-8.1309440;3.3912062;-0.0207310;8.0000000;0.0000000 +28.1942423;-27.2685495;-8.1799123;3.3866831;-0.0245107;8.0000000;0.0000000 +28.3942014;-27.4626604;-8.2279320;3.3814039;-0.0282908;8.0000000;0.0000000 +28.5941606;-27.6570369;-8.2748522;3.3753719;-0.0320240;8.0000000;0.0000000 +28.7941198;-27.8517090;-8.3205266;3.3685979;-0.0357296;8.0000000;0.0000000 +28.9940789;-28.0467060;-8.3648098;3.3610827;-0.0394341;8.0000000;0.0000000 +29.1940381;-28.2420422;-8.4075534;3.3528291;-0.0431200;8.0000000;0.0000000 +29.3939973;-28.4377406;-8.4486112;3.3438379;-0.0468107;8.0000000;0.0000000 +29.5939564;-28.6338161;-8.4878359;3.3341088;-0.0504978;8.0000000;0.0000000 +29.7939156;-28.8302765;-8.5250784;3.3236423;-0.0541892;8.0000000;0.0000000 +29.9938747;-29.0271261;-8.5601894;3.3124371;-0.0578859;8.0000000;0.0000000 +30.1938339;-29.2243760;-8.5930209;3.3004927;-0.0615821;8.0000000;0.0000000 +30.3937931;-29.4220067;-8.6234196;3.2878083;-0.0652915;8.0000000;0.0000000 +30.5937522;-29.6200241;-8.6512365;3.2743813;-0.0690022;8.0000000;0.0000000 +30.7937114;-29.8184047;-8.6763184;3.2602114;-0.0727271;8.0000000;0.0000000 +30.9936706;-30.0171191;-8.6985117;3.2452957;-0.0764659;8.0000000;0.0000000 +31.1936297;-30.2161691;-8.7176659;3.2296308;-0.0802105;8.0000000;0.0000000 +31.3935889;-30.4154814;-8.7336237;3.2132159;-0.0839823;8.0000000;0.0000000 +31.5935481;-30.6150463;-8.7462330;3.1960443;-0.0877633;8.0000000;0.0000000 +31.7935072;-30.8147992;-8.7553381;3.1781145;-0.0915739;8.0000000;0.0000000 +31.9934664;-31.0146677;-8.7607837;3.1594211;-0.0954114;8.0000000;0.0000000 +32.1934256;-31.2146361;-8.7624156;3.1399570;-0.0992597;8.0000000;0.0000000 +32.3933847;-31.4145673;-8.7600786;3.1197214;-0.1031558;8.0000000;0.0000000 +32.5933439;-31.6144263;-8.7536178;3.0987023;-0.1070700;8.0000000;0.0000000 +32.7933031;-31.8140979;-8.7428797;3.0768968;-0.1110342;8.0000000;0.0000000 +32.9932622;-32.0134577;-8.7277133;3.0542958;-0.1150466;8.0000000;0.0000000 +33.1932214;-32.2124583;-8.7079607;3.0308852;-0.1190934;8.0000000;0.0000000 +33.3931805;-32.4108939;-8.6834796;3.0066621;-0.1232163;8.0000000;0.0000000 +33.5931397;-32.6086877;-8.6541140;2.9816039;-0.1274302;8.0000000;0.0000000 +33.7930989;-32.8056656;-8.6197185;2.9556913;-0.1317578;8.0000000;0.0000000 +33.9930580;-33.0016435;-8.5801511;2.9289081;-0.1361847;8.0000000;0.0000000 +34.1930172;-33.1965145;-8.5352512;2.9012102;-0.1408404;8.0000000;0.0000000 +34.3929764;-33.3900054;-8.4848914;2.8725743;-0.1456162;8.0000000;0.0000000 +34.5929355;-33.5819657;-8.4289187;2.8430647;-0.1490357;8.0000000;0.0000000 +34.7928947;-33.7721723;-8.3672515;2.8129917;-0.1517739;8.0000000;0.0000000 +34.9928539;-33.9604004;-8.2998481;2.7823784;-0.1535787;8.0000000;0.0000000 +35.1928130;-34.1464911;-8.2267195;2.7520722;-0.1495696;8.0000000;0.0000000 +35.3927722;-34.3303225;-8.1480539;2.7225572;-0.1456535;8.0000000;0.0000000 +35.5927314;-34.5117681;-8.0640782;2.6938599;-0.1411925;8.0000000;0.0000000 +35.7926905;-34.6907816;-7.9750089;2.6661015;-0.1364693;8.0000000;0.0000000 +35.9926497;-34.8673184;-7.8810771;2.6392743;-0.1318691;8.0000000;0.0000000 +36.1926089;-35.0412763;-7.7825460;2.6133524;-0.1274524;8.0000000;0.0000000 +36.3925680;-35.2127104;-7.6795878;2.5882998;-0.1231136;8.0000000;0.0000000 +36.5925272;-35.3815280;-7.5724596;2.5641106;-0.1188530;8.0000000;0.0000000 +36.7924864;-35.5477614;-7.4613438;2.5407668;-0.1146479;8.0000000;0.0000000 +36.9924455;-35.7114288;-7.3464286;2.5182532;-0.1105171;8.0000000;0.0000000 +37.1924047;-35.8724724;-7.2279576;2.4965660;-0.1064387;8.0000000;0.0000000 +37.3923638;-36.0309994;-7.1060543;2.4756836;-0.1024154;8.0000000;0.0000000 +37.5923230;-36.1869712;-6.9809506;2.4556047;-0.0984223;8.0000000;0.0000000 +37.7922822;-36.3404573;-6.8527964;2.4363218;-0.0944562;8.0000000;0.0000000 +37.9922413;-36.4915146;-6.7217493;2.4178247;-0.0905349;8.0000000;0.0000000 +38.1922005;-36.6401432;-6.5880178;2.4001146;-0.0866255;8.0000000;0.0000000 +38.3921597;-36.7864599;-6.4517070;2.3831797;-0.0827512;8.0000000;0.0000000 +38.5921188;-36.9304864;-6.3130076;2.3670184;-0.0788969;8.0000000;0.0000000 +38.7920780;-37.0723096;-6.1720510;2.3516265;-0.0750587;8.0000000;0.0000000 +38.9920372;-37.2120113;-6.0289710;2.3369982;-0.0712453;8.0000000;0.0000000 +39.1919963;-37.3496462;-5.8839307;2.3231342;-0.0674304;8.0000000;0.0000000 +39.3919555;-37.4853225;-5.7370374;2.3100303;-0.0636346;8.0000000;0.0000000 +39.5919147;-37.6191161;-5.5884326;2.2976847;-0.0598421;8.0000000;0.0000000 +39.7918738;-37.7511209;-5.4382385;2.2860977;-0.0560533;8.0000000;0.0000000 +39.9918330;-37.8814352;-5.2865729;2.2752671;-0.0522674;8.0000000;0.0000000 +40.1917922;-38.0101588;-5.1335521;2.2651982;-0.0484402;8.0000000;0.0000000 +40.3917513;-38.1373896;-4.9792971;2.2558944;-0.0446199;8.0000000;0.0000000 +40.5917105;-38.2632462;-4.8239048;2.2473589;-0.0407220;8.0000000;0.0000000 +40.7916697;-38.3878299;-4.6674970;2.2396095;-0.0367881;8.0000000;0.0000000 +40.9916288;-38.5112527;-4.5101859;2.2326447;-0.0329658;8.0000000;0.0000000 +41.1915880;-38.6336475;-4.3520460;2.2263854;-0.0296353;8.0000000;0.0000000 +41.3915471;-38.7550890;-4.1932018;2.2207930;-0.0263021;8.0000000;0.0000000 +41.5915063;-38.8756991;-4.0337139;2.2158671;-0.0229675;8.0000000;0.0000000 +41.7914655;-38.9955754;-3.8736737;2.2116083;-0.0196288;8.0000000;0.0000000 +41.9914246;-39.1148198;-3.7131680;2.2080096;-0.0167279;8.0000000;0.0000000 +42.1913838;-39.2335226;-3.5522545;2.2047526;-0.0158485;8.0000000;0.0000000 +42.3913430;-39.3517151;-3.3909652;2.2016715;-0.0149690;8.0000000;0.0000000 +42.5913021;-39.4694231;-3.2293221;2.1987319;-0.0145939;8.0000000;0.0000000 +42.7912613;-39.5866587;-3.0673361;2.1958275;-0.0144566;8.0000000;0.0000000 +42.9912205;-39.7034256;-2.9050117;2.1929505;-0.0143194;8.0000000;0.0000000 +43.1911796;-39.8197272;-2.7423538;2.1901009;-0.0141818;8.0000000;0.0000000 +43.3911388;-39.9355670;-2.5793668;2.1872789;-0.0140442;8.0000000;0.0000000 +43.5910980;-40.0509486;-2.4160553;2.1844844;-0.0139070;8.0000000;0.0000000 +43.7910571;-40.1658756;-2.2524234;2.1817172;-0.0137701;8.0000000;0.0000000 +43.9910163;-40.2803518;-2.0884755;2.1789775;-0.0136333;8.0000000;0.0000000 +44.1909755;-40.3943804;-1.9242165;2.1762650;-0.0134969;8.0000000;0.0000000 +44.3909346;-40.5079655;-1.7596500;2.1735798;-0.0133605;8.0000000;0.0000000 +44.5908938;-40.6211104;-1.5947809;2.1709219;-0.0132245;8.0000000;0.0000000 +44.7908530;-40.7338189;-1.4296131;2.1682911;-0.0130886;8.0000000;0.0000000 +44.9908121;-40.8460950;-1.2641506;2.1656875;-0.0129529;8.0000000;0.0000000 +45.1907713;-40.9579418;-1.0983985;2.1631110;-0.0128175;8.0000000;0.0000000 +45.3907304;-41.0693638;-0.9323596;2.1605616;-0.0126821;8.0000000;0.0000000 +45.5906896;-41.1803640;-0.7660391;2.1580392;-0.0125471;8.0000000;0.0000000 +45.7906488;-41.2909468;-0.5994406;2.1555438;-0.0124122;8.0000000;0.0000000 +45.9906079;-41.4011159;-0.4325677;2.1530753;-0.0122774;8.0000000;0.0000000 +46.1905671;-41.5108746;-0.2654256;2.1506338;-0.0121430;8.0000000;0.0000000 +46.3905263;-41.6202276;-0.0980168;2.1482191;-0.0120086;8.0000000;0.0000000 +46.5904854;-41.7291779;0.0696537;2.1458313;-0.0118744;8.0000000;0.0000000 +46.7904446;-41.8377299;0.2375825;2.1434703;-0.0117405;8.0000000;0.0000000 +46.9904038;-41.9458877;0.4057660;2.1411361;-0.0116066;8.0000000;0.0000000 +47.1903629;-42.0536543;0.5741994;2.1388286;-0.0114730;8.0000000;0.0000000 +47.3903221;-42.1610348;0.7428803;2.1365478;-0.0113395;8.0000000;0.0000000 +47.5902813;-42.2680321;0.9118037;2.1342937;-0.0112062;8.0000000;0.0000000 +47.7902404;-42.3746507;1.0809667;2.1320662;-0.0110731;8.0000000;0.0000000 +47.9901996;-42.4808948;1.2503657;2.1298653;-0.0109400;8.0000000;0.0000000 +48.1901588;-42.5867676;1.4199959;2.1276911;-0.0108073;8.0000000;0.0000000 +48.3901179;-42.6922740;1.5898552;2.1255433;-0.0106745;8.0000000;0.0000000 +48.5900771;-42.7974173;1.7599389;2.1234221;-0.0105420;8.0000000;0.0000000 +48.7900363;-42.9022019;1.9302439;2.1213274;-0.0104097;8.0000000;0.0000000 +48.9899954;-43.0066321;2.1007671;2.1192591;-0.0102774;8.0000000;0.0000000 +49.1899546;-43.1107111;2.2715039;2.1172172;-0.0101453;8.0000000;0.0000000 +49.3899137;-43.2144440;2.4424521;2.1152018;-0.0100133;8.0000000;0.0000000 +49.5898729;-43.3178341;2.6136072;2.1132127;-0.0098816;8.0000000;0.0000000 +49.7898321;-43.4208859;2.7849663;2.1112499;-0.0097499;8.0000000;0.0000000 +49.9897912;-43.5236037;2.9565264;2.1093135;-0.0096183;8.0000000;0.0000000 +50.1897504;-43.6259909;3.1282832;2.1074034;-0.0094869;8.0000000;0.0000000 +50.3897096;-43.7280524;3.3002343;2.1055195;-0.0093556;8.0000000;0.0000000 +50.5896687;-43.8297919;3.4723758;2.1036619;-0.0092245;8.0000000;0.0000000 +50.7896279;-43.9312138;3.6447047;2.1018305;-0.0090935;8.0000000;0.0000000 +50.9895871;-44.0323222;3.8172180;2.1000253;-0.0089625;8.0000000;0.0000000 +51.1895462;-44.1331211;3.9899119;2.0982462;-0.0088317;8.0000000;0.0000000 +51.3895054;-44.2336151;4.1627838;2.0964933;-0.0087009;8.0000000;0.0000000 +51.5894646;-44.3338080;4.3358301;2.0947665;-0.0085704;8.0000000;0.0000000 +51.7894237;-44.4337043;4.5090478;2.0930658;-0.0084401;8.0000000;0.0000000 +51.9893829;-44.5333081;4.6824341;2.0913912;-0.0083097;8.0000000;0.0000000 +52.1893421;-44.6326236;4.8559854;2.0897426;-0.0081796;8.0000000;0.0000000 +52.3893012;-44.7316552;5.0296991;2.0881200;-0.0080494;8.0000000;0.0000000 +52.5892604;-44.8304070;5.2035719;2.0865235;-0.0079194;8.0000000;0.0000000 +52.7892196;-44.9288834;5.3776008;2.0849529;-0.0077894;8.0000000;0.0000000 +52.9891787;-45.0270886;5.5517829;2.0834083;-0.0076596;8.0000000;0.0000000 +53.1891379;-45.1250269;5.7261154;2.0818897;-0.0075299;8.0000000;0.0000000 +53.3890970;-45.2227025;5.9005948;2.0803970;-0.0074002;8.0000000;0.0000000 +53.5890562;-45.3201200;6.0752189;2.0789302;-0.0072707;8.0000000;0.0000000 +53.7890154;-45.4172835;6.2499843;2.0774893;-0.0071412;8.0000000;0.0000000 +53.9889745;-45.5141971;6.4248881;2.0760743;-0.0070118;8.0000000;0.0000000 +54.1889337;-45.6108658;6.5999281;2.0746851;-0.0068825;8.0000000;0.0000000 +54.3888929;-45.7072931;6.7751003;2.0733218;-0.0067533;8.0000000;0.0000000 +54.5888520;-45.8034840;6.9504032;2.0719844;-0.0066242;8.0000000;0.0000000 +54.7888112;-45.8994426;7.1258331;2.0706727;-0.0064952;8.0000000;0.0000000 +54.9887704;-45.9951730;7.3013870;2.0693868;-0.0063663;8.0000000;0.0000000 +55.1887295;-46.0906804;7.4770636;2.0681267;-0.0062374;8.0000000;0.0000000 +55.3886887;-46.1859680;7.6528582;2.0668923;-0.0061086;8.0000000;0.0000000 +55.5886479;-46.2810413;7.8287699;2.0656837;-0.0059799;8.0000000;0.0000000 +55.7886070;-46.3759040;8.0047948;2.0645008;-0.0058513;8.0000000;0.0000000 +55.9885662;-46.4705603;8.1809299;2.0633437;-0.0057228;8.0000000;0.0000000 +56.1885254;-46.5650158;8.3571747;2.0622122;-0.0055943;8.0000000;0.0000000 +56.3884845;-46.6592732;8.5335235;2.0611064;-0.0054659;8.0000000;0.0000000 +56.5884437;-46.7533385;8.7099764;2.0600263;-0.0053376;8.0000000;0.0000000 +56.7884029;-46.8472152;8.8865292;2.0589718;-0.0052094;8.0000000;0.0000000 +56.9883620;-46.9409075;9.0631788;2.0579429;-0.0050812;8.0000000;0.0000000 +57.1883212;-47.0344212;9.2399253;2.0569397;-0.0049531;8.0000000;0.0000000 +57.3882803;-47.1277588;9.4167625;2.0559621;-0.0048250;8.0000000;0.0000000 +57.5882395;-47.2209265;9.5936911;2.0550101;-0.0046971;8.0000000;0.0000000 +57.7881987;-47.3139277;9.7707066;2.0540837;-0.0045692;8.0000000;0.0000000 +57.9881578;-47.4067666;9.9478060;2.0531828;-0.0044413;8.0000000;0.0000000 +58.1881170;-47.4994494;10.1249900;2.0523075;-0.0043135;8.0000000;0.0000000 +58.3880762;-47.5919781;10.3022515;2.0514578;-0.0041858;8.0000000;0.0000000 +58.5880353;-47.6843593;10.4795922;2.0506335;-0.0040582;8.0000000;0.0000000 +58.7879945;-47.7765963;10.6570072;2.0498348;-0.0039306;8.0000000;0.0000000 +58.9879537;-47.8686931;10.8344933;2.0490616;-0.0038031;8.0000000;0.0000000 +59.1879128;-47.9606563;11.0120521;2.0483139;-0.0036756;8.0000000;0.0000000 +59.3878720;-48.0524876;11.1896757;2.0475916;-0.0035482;8.0000000;0.0000000 +59.5878312;-48.1441939;11.3673665;2.0468949;-0.0034209;8.0000000;0.0000000 +59.7877903;-48.2357782;11.5451193;2.0462236;-0.0032937;8.0000000;0.0000000 +59.9877495;-48.3272447;11.7229309;2.0455777;-0.0031664;8.0000000;0.0000000 +60.1877087;-48.4186002;11.9008034;2.0449572;-0.0030393;8.0000000;0.0000000 +60.3876678;-48.5098460;12.0787282;2.0443622;-0.0029122;8.0000000;0.0000000 +60.5876270;-48.6009893;12.2567086;2.0437926;-0.0027852;8.0000000;0.0000000 +60.7875862;-48.6920331;12.4347389;2.0432483;-0.0026583;8.0000000;0.0000000 +60.9875453;-48.7829814;12.6128158;2.0427295;-0.0025314;8.0000000;0.0000000 +61.1875045;-48.8738413;12.7909422;2.0422360;-0.0024046;8.0000000;0.0000000 +61.3874636;-48.9646138;12.9691088;2.0417678;-0.0022778;8.0000000;0.0000000 +61.5874228;-49.0553065;13.1473194;2.0413250;-0.0021511;8.0000000;0.0000000 +61.7873820;-49.1459220;13.3255680;2.0409076;-0.0020245;8.0000000;0.0000000 +61.9873411;-49.2364644;13.5038516;2.0405154;-0.0018979;8.0000000;0.0000000 +62.1873003;-49.3269411;13.6821731;2.0401486;-0.0017714;8.0000000;0.0000000 +62.3872595;-49.4173527;13.8605229;2.0398070;-0.0016449;8.0000000;0.0000000 +62.5872186;-49.5077070;14.0389054;2.0394907;-0.0015186;8.0000000;0.0000000 +62.7871778;-49.5980067;14.2173142;2.0391997;-0.0013923;8.0000000;0.0000000 +62.9871370;-49.6882558;14.3957463;2.0389339;-0.0012660;8.0000000;0.0000000 +63.1870961;-49.7784616;14.5742051;2.0386934;-0.0011399;8.0000000;0.0000000 +63.3870553;-49.8686248;14.7526805;2.0384781;-0.0010137;8.0000000;0.0000000 +63.5870145;-49.9587533;14.9311772;2.0382880;-0.0008877;8.0000000;0.0000000 +63.7869736;-50.0488496;15.1096889;2.0381230;-0.0007617;8.0000000;0.0000000 +63.9869328;-50.1389177;15.2882123;2.0379833;-0.0006358;8.0000000;0.0000000 +64.1868920;-50.2289652;15.4667512;2.0378688;-0.0005100;8.0000000;0.0000000 +64.3868511;-50.3189923;15.6452951;2.0377794;-0.0003842;8.0000000;0.0000000 +64.5868103;-50.4090074;15.8238491;2.0377151;-0.0002586;8.0000000;0.0000000 +64.7867695;-50.4990126;16.0024066;2.0376759;-0.0001332;8.0000000;0.0000000 +64.9867286;-50.5890121;16.1809647;2.0376618;-0.0000081;8.0000000;0.0000000 +65.1866878;-50.6790134;16.3595269;2.0376726;0.0001158;8.0000000;0.0000000 +65.3866469;-50.7690167;16.5380828;2.0377081;0.0002397;8.0000000;0.0000000 +65.5866061;-50.8590301;16.7166377;2.0377682;0.0003598;8.0000000;0.0000000 +65.7865653;-50.9490558;16.8951848;2.0378520;0.0004785;8.0000000;0.0000000 +65.9865244;-51.0390975;17.0737213;2.0379598;0.0006072;8.0000000;0.0000000 +66.1864836;-51.1291629;17.2522504;2.0380976;0.0007711;8.0000000;0.0000000 +66.3864428;-51.2192542;17.4307624;2.0382682;0.0009351;8.0000000;0.0000000 +66.5864019;-51.3093801;17.6092600;2.0384715;0.0010980;8.0000000;0.0000000 +66.7863611;-51.3995447;17.7877370;2.0387073;0.0012605;8.0000000;0.0000000 +66.9863203;-51.4897537;17.9661900;2.0389755;0.0014204;8.0000000;0.0000000 +67.1862794;-51.5800148;18.1446203;2.0392746;0.0015709;8.0000000;0.0000000 +67.3862386;-51.6703304;18.3230190;2.0396038;0.0017215;8.0000000;0.0000000 +67.5861978;-51.7607086;18.5013892;2.0399631;0.0018719;8.0000000;0.0000000 +67.7861569;-51.8511531;18.6797245;2.0403524;0.0020223;8.0000000;0.0000000 +67.9861161;-51.9416690;18.8580219;2.0407718;0.0021725;8.0000000;0.0000000 +68.1860753;-52.0322638;19.0362828;2.0412212;0.0023227;8.0000000;0.0000000 +68.3860344;-52.1229398;19.2144986;2.0417007;0.0024728;8.0000000;0.0000000 +68.5859936;-52.2137053;19.3926720;2.0422101;0.0026228;8.0000000;0.0000000 +68.7859527;-52.3045636;19.5707968;2.0427496;0.0027727;8.0000000;0.0000000 +68.9859119;-52.3955201;19.7488699;2.0433190;0.0029225;8.0000000;0.0000000 +69.1858711;-52.4865819;19.9268926;2.0439183;0.0030722;8.0000000;0.0000000 +69.3858302;-52.5777517;20.1048564;2.0445476;0.0032219;8.0000000;0.0000000 +69.5857894;-52.6690373;20.2827637;2.0452068;0.0033715;8.0000000;0.0000000 +69.7857486;-52.7604423;20.4606086;2.0458959;0.0035210;8.0000000;0.0000000 +69.9857077;-52.8519719;20.6383880;2.0466149;0.0036704;8.0000000;0.0000000 +70.1856669;-52.9436333;20.8161025;2.0473638;0.0038197;8.0000000;0.0000000 +70.3856261;-53.0354290;20.9937444;2.0481425;0.0039690;8.0000000;0.0000000 +70.5855852;-53.1273667;21.1713155;2.0489511;0.0041182;8.0000000;0.0000000 +70.7855444;-53.2194502;21.3488100;2.0497894;0.0042673;8.0000000;0.0000000 +70.9855036;-53.3116847;21.5262249;2.0506576;0.0044163;8.0000000;0.0000000 +71.1854627;-53.4040768;21.7035603;2.0515556;0.0045652;8.0000000;0.0000000 +71.3854219;-53.4966297;21.8808091;2.0524833;0.0047141;8.0000000;0.0000000 +71.5853811;-53.5893505;22.0579725;2.0534408;0.0048628;8.0000000;0.0000000 +71.7853402;-53.6822432;22.2350448;2.0544281;0.0050115;8.0000000;0.0000000 +71.9852994;-53.7753128;22.4120232;2.0554450;0.0051601;8.0000000;0.0000000 +72.1852586;-53.8685659;22.5889072;2.0564917;0.0053086;8.0000000;0.0000000 +72.3852177;-53.9620057;22.7656901;2.0575680;0.0054571;8.0000000;0.0000000 +72.5851769;-54.0556393;22.9423727;2.0586741;0.0056055;8.0000000;0.0000000 +72.7851360;-54.1494704;23.1189495;2.0598098;0.0057538;8.0000000;0.0000000 +72.9850952;-54.2435043;23.2954176;2.0609751;0.0059021;8.0000000;0.0000000 +73.1850544;-54.3377472;23.4717760;2.0621701;0.0060502;8.0000000;0.0000000 +73.3850135;-54.4322025;23.6480186;2.0633947;0.0061983;8.0000000;0.0000000 +73.5849727;-54.5268769;23.8241455;2.0646489;0.0063463;8.0000000;0.0000000 +73.7849319;-54.6217744;24.0001515;2.0659327;0.0064942;8.0000000;0.0000000 +73.9848910;-54.7169001;24.1760336;2.0672460;0.0066421;8.0000000;0.0000000 +74.1848502;-54.8122600;24.3517904;2.0685890;0.0067899;8.0000000;0.0000000 +74.3848094;-54.9078577;24.5274162;2.0699614;0.0069376;8.0000000;0.0000000 +74.5847685;-55.0036995;24.7029104;2.0713634;0.0070853;8.0000000;0.0000000 +74.7847277;-55.0997896;24.8782681;2.0727950;0.0072328;8.0000000;0.0000000 +74.9846869;-55.1961330;25.0534863;2.0742560;0.0073804;8.0000000;0.0000000 +75.1846460;-55.2927354;25.2285630;2.0757465;0.0075278;8.0000000;0.0000000 +75.3846052;-55.3896007;25.4034931;2.0772665;0.0076752;8.0000000;0.0000000 +75.5845644;-55.4867348;25.5782751;2.0788160;0.0078225;8.0000000;0.0000000 +75.7845235;-55.5841419;25.7529047;2.0803949;0.0079698;8.0000000;0.0000000 +75.9844827;-55.6818271;25.9273786;2.0820032;0.0081170;8.0000000;0.0000000 +76.1844419;-55.7797957;26.1016942;2.0836410;0.0082641;8.0000000;0.0000000 +76.3844010;-55.8780518;26.2758471;2.0853082;0.0084113;8.0000000;0.0000000 +76.5843602;-55.9766010;26.4498350;2.0870048;0.0085582;8.0000000;0.0000000 +76.7843193;-56.0754477;26.6236538;2.0887308;0.0087052;8.0000000;0.0000000 +76.9842785;-56.1745967;26.7973002;2.0904862;0.0088522;8.0000000;0.0000000 +77.1842377;-56.2740531;26.9707710;2.0922709;0.0089990;8.0000000;0.0000000 +77.3841968;-56.3738213;27.1440624;2.0940851;0.0091458;8.0000000;0.0000000 +77.5841560;-56.4739064;27.3171712;2.0959285;0.0092926;8.0000000;0.0000000 +77.7841152;-56.5743129;27.4900936;2.0978013;0.0094393;8.0000000;0.0000000 +77.9840743;-56.6750456;27.6628262;2.0997035;0.0095860;8.0000000;0.0000000 +78.1840335;-56.7761093;27.8353654;2.1016349;0.0097326;8.0000000;0.0000000 +78.3839927;-56.8775085;28.0077077;2.1035957;0.0098792;8.0000000;0.0000000 +78.5839518;-56.9792480;28.1798492;2.1055858;0.0100258;8.0000000;0.0000000 +78.7839110;-57.0813324;28.3517864;2.1076052;0.0101723;8.0000000;0.0000000 +78.9838702;-57.1837663;28.5235157;2.1096539;0.0103188;8.0000000;0.0000000 +79.1838293;-57.2865542;28.6950332;2.1117319;0.0104652;8.0000000;0.0000000 +79.3837885;-57.3897011;28.8663354;2.1138391;0.0106117;8.0000000;0.0000000 +79.5837477;-57.4932109;29.0374180;2.1159757;0.0107581;8.0000000;0.0000000 +79.7837068;-57.5970887;29.2082778;2.1181415;0.0109045;8.0000000;0.0000000 +79.9836660;-57.7013388;29.3789108;2.1203366;0.0110509;8.0000000;0.0000000 +80.1836252;-57.8059655;29.5493126;2.1225609;0.0111972;8.0000000;0.0000000 +80.3835843;-57.9109739;29.7194803;2.1248146;0.0113436;8.0000000;0.0000000 +80.5835435;-58.0163675;29.8894088;2.1270974;0.0114900;8.0000000;0.0000000 +80.7835026;-58.1221515;30.0590950;2.1294096;0.0116363;8.0000000;0.0000000 +80.9834618;-58.2283301;30.2285347;2.1317510;0.0117827;8.0000000;0.0000000 +81.1834210;-58.3349073;30.3977233;2.1341217;0.0119291;8.0000000;0.0000000 +81.3833801;-58.4418883;30.5666580;2.1365217;0.0120755;8.0000000;0.0000000 +81.5833393;-58.5492763;30.7353330;2.1389510;0.0122219;8.0000000;0.0000000 +81.7832985;-58.6570766;30.9037455;2.1414095;0.0123684;8.0000000;0.0000000 +81.9832576;-58.7652931;31.0718911;2.1438973;0.0125149;8.0000000;0.0000000 +82.1832168;-58.8739296;31.2397647;2.1464144;0.0126615;8.0000000;0.0000000 +82.3831760;-58.9829915;31.4073637;2.1489609;0.0128081;8.0000000;0.0000000 +82.5831351;-59.0924815;31.5746817;2.1515366;0.0129547;8.0000000;0.0000000 +82.7830943;-59.2024050;31.7417162;2.1541417;0.0131015;8.0000000;0.0000000 +82.9830535;-59.3127658;31.9084623;2.1567761;0.0132483;8.0000000;0.0000000 +83.1830126;-59.4235674;32.0749147;2.1594399;0.0133951;8.0000000;0.0000000 +83.3829718;-59.5348153;32.2410709;2.1621331;0.0135421;8.0000000;0.0000000 +83.5829310;-59.6465118;32.4069239;2.1648557;0.0136892;8.0000000;0.0000000 +83.7828901;-59.7586624;32.5724713;2.1676077;0.0138364;8.0000000;0.0000000 +83.9828493;-59.8712707;32.7377080;2.1703891;0.0139837;8.0000000;0.0000000 +84.1828085;-59.9843400;32.9026283;2.1732000;0.0141311;8.0000000;0.0000000 +84.3827676;-60.0978758;33.0672298;2.1760404;0.0142786;8.0000000;0.0000000 +84.5827268;-60.2118800;33.2315049;2.1789103;0.0144264;8.0000000;0.0000000 +84.7826859;-60.3263583;33.3954514;2.1818098;0.0145744;8.0000000;0.0000000 +84.9826451;-60.4413139;33.5590637;2.1847389;0.0147229;8.0000000;0.0000000 +85.1826043;-60.5567501;33.7223360;2.1876978;0.0148723;8.0000000;0.0000000 +85.3825634;-60.6726724;33.8852657;2.1906866;0.0150218;8.0000000;0.0000000 +85.5825226;-60.7890824;34.0478448;2.1937054;0.0151728;8.0000000;0.0000000 +85.7824818;-60.9059857;34.2100710;2.1967545;0.0153242;8.0000000;0.0000000 +85.9824409;-61.0233857;34.3719382;2.1998339;0.0154762;8.0000000;0.0000000 +86.1824001;-61.1412855;34.5334406;2.2029438;0.0156294;8.0000000;0.0000000 +86.3823593;-61.2596904;34.6945752;2.2060843;0.0157826;8.0000000;0.0000000 +86.5823184;-61.3786021;34.8553336;2.2092557;0.0159373;8.0000000;0.0000000 +86.7822776;-61.4980262;35.0157132;2.2124580;0.0160923;8.0000000;0.0000000 +86.9822368;-61.6179658;35.1757077;2.2156913;0.0162479;8.0000000;0.0000000 +87.1821959;-61.7384240;35.3353110;2.2189559;0.0164046;8.0000000;0.0000000 +87.3821551;-61.8594061;35.4945196;2.2222518;0.0165614;8.0000000;0.0000000 +87.5821143;-61.9809135;35.6533252;2.2255792;0.0167194;8.0000000;0.0000000 +87.7820734;-62.1029520;35.8117245;2.2289382;0.0168778;8.0000000;0.0000000 +87.9820326;-62.2255243;35.9697111;2.2323289;0.0170369;8.0000000;0.0000000 +88.1819918;-62.3486336;36.1272787;2.2357516;0.0171970;8.0000000;0.0000000 +88.3819509;-62.4722849;36.2844230;2.2392064;0.0173574;8.0000000;0.0000000 +88.5819101;-62.5964799;36.4411359;2.2426932;0.0175180;8.0000000;0.0000000 +88.7818692;-62.7212236;36.5974136;2.2462121;0.0176788;8.0000000;0.0000000 +88.9818284;-62.8465190;36.7532494;2.2497636;0.0178493;8.0000000;0.0000000 +89.1817876;-62.9723695;36.9086365;2.2533513;0.0180345;8.0000000;0.0000000 +89.3817467;-63.0987802;37.0635695;2.2569760;0.0182202;8.0000000;0.0000000 +89.5817059;-63.2257535;37.2180400;2.2606358;0.0183834;8.0000000;0.0000000 +89.7816651;-63.3532943;37.3720433;2.2643278;0.0185442;8.0000000;0.0000000 +89.9816242;-63.4814048;37.5255723;2.2680445;0.0185194;8.0000000;0.0000000 +90.1815834;-63.6100819;37.6786258;2.2717178;0.0182212;8.0000000;0.0000000 +90.3815426;-63.7393179;37.8312116;2.2753315;0.0179230;8.0000000;0.0000000 +90.5815017;-63.8690970;37.9833307;2.2788795;0.0175583;8.0000000;0.0000000 +90.7814609;-63.9994111;38.1349951;2.2823533;0.0171872;8.0000000;0.0000000 +90.9814201;-64.1302458;38.2862109;2.2857531;0.0168189;8.0000000;0.0000000 +91.1813792;-64.2615873;38.4369847;2.2890797;0.0164541;8.0000000;0.0000000 +91.3813384;-64.3934257;38.5873273;2.2923334;0.0160894;8.0000000;0.0000000 +91.5812976;-64.5257452;38.7372428;2.2955142;0.0157249;8.0000000;0.0000000 +91.7812567;-64.6585366;38.8867428;2.2986221;0.0153605;8.0000000;0.0000000 +91.9812159;-64.7917865;39.0358341;2.3016571;0.0149964;8.0000000;0.0000000 +92.1811751;-64.9254822;39.1845246;2.3046194;0.0146328;8.0000000;0.0000000 +92.3811342;-65.0596137;39.3328245;2.3075091;0.0142693;8.0000000;0.0000000 +92.5810934;-65.1941663;39.4807396;2.3103261;0.0139066;8.0000000;0.0000000 +92.7810525;-65.3291305;39.6282808;2.3130706;0.0135441;8.0000000;0.0000000 +92.9810117;-65.4644937;39.7754559;2.3157426;0.0131819;8.0000000;0.0000000 +93.1809709;-65.6002440;39.9222732;2.3183423;0.0128201;8.0000000;0.0000000 +93.3809300;-65.7363712;40.0687431;2.3208696;0.0124584;8.0000000;0.0000000 +93.5808892;-65.8728616;40.2148720;2.3233247;0.0120973;8.0000000;0.0000000 +93.7808484;-66.0097058;40.3606712;2.3257076;0.0117363;8.0000000;0.0000000 +93.9808075;-66.1468918;40.5061488;2.3280183;0.0113756;8.0000000;0.0000000 +94.1807667;-66.2844078;40.6513135;2.3302569;0.0110153;8.0000000;0.0000000 +94.3807259;-66.4222444;40.7961760;2.3324235;0.0106551;8.0000000;0.0000000 +94.5806850;-66.5603878;40.9407431;2.3345181;0.0102953;8.0000000;0.0000000 +94.7806442;-66.6988295;41.0850264;2.3365408;0.0099357;8.0000000;0.0000000 +94.9806034;-66.8375574;41.2290343;2.3384916;0.0095763;8.0000000;0.0000000 +95.1805625;-66.9765604;41.3727758;2.3403706;0.0092173;8.0000000;0.0000000 +95.3805217;-67.1158292;41.5162620;2.3421778;0.0088583;8.0000000;0.0000000 +95.5804809;-67.2553504;41.6594997;2.3439132;0.0084999;8.0000000;0.0000000 +95.7804400;-67.3951159;41.8025011;2.3455771;0.0081415;8.0000000;0.0000000 +95.9803992;-67.5351138;41.9452746;2.3471692;0.0077833;8.0000000;0.0000000 +96.1803584;-67.6753333;42.0878296;2.3486897;0.0074252;8.0000000;0.0000000 +96.3803175;-67.8157656;42.2301776;2.3501387;0.0070671;8.0000000;0.0000000 +96.5802767;-67.9563971;42.3723251;2.3515161;0.0067098;8.0000000;0.0000000 +96.7802358;-68.0972204;42.5142850;2.3528220;0.0063525;8.0000000;0.0000000 +96.9801950;-68.2382237;42.6560658;2.3540566;0.0059956;8.0000000;0.0000000 +97.1801542;-68.3793963;42.7976768;2.3552198;0.0056392;8.0000000;0.0000000 +97.3801133;-68.5207301;42.9391301;2.3563118;0.0052828;8.0000000;0.0000000 +97.5800725;-68.6622110;43.0804319;2.3573325;0.0049271;8.0000000;0.0000000 +97.7800317;-68.8038325;43.2215956;2.3582822;0.0045714;8.0000000;0.0000000 +97.9799908;-68.9455828;43.3626296;2.3591608;0.0042162;8.0000000;0.0000000 +98.1799500;-69.0874513;43.5035434;2.3599684;0.0038615;8.0000000;0.0000000 +98.3799092;-69.2294302;43.6443493;2.3607050;0.0035068;8.0000000;0.0000000 +98.5798683;-69.3715056;43.7850533;2.3613709;0.0031532;8.0000000;0.0000000 +98.7798275;-69.5136711;43.9256692;2.3619660;0.0027996;8.0000000;0.0000000 +98.9797867;-69.6559150;44.0662052;2.3624905;0.0024466;8.0000000;0.0000000 +99.1797458;-69.7982271;44.2066711;2.3629445;0.0020943;8.0000000;0.0000000 +99.3797050;-69.9405998;44.3470790;2.3633281;0.0017420;8.0000000;0.0000000 +99.5796642;-70.0830189;44.4874349;2.3636413;0.0013912;8.0000000;0.0000000 +99.7796233;-70.2254786;44.6277528;2.3638845;0.0010405;8.0000000;0.0000000 +99.9795825;-70.3679673;44.7680407;2.3640575;0.0006907;8.0000000;0.0000000 +100.1795416;-70.5104747;44.9083084;2.3641608;0.0003420;8.0000000;0.0000000 +100.3795008;-70.6529935;45.0485680;2.3641943;-0.0000068;8.0000000;0.0000000 +100.5794600;-70.7955096;45.1888255;2.3641583;-0.0003533;8.0000000;0.0000000 +100.7794191;-70.9380174;45.3290945;2.3640530;-0.0006998;8.0000000;0.0000000 +100.9793783;-71.0805054;45.4693832;2.3638785;-0.0010444;8.0000000;0.0000000 +101.1793375;-71.2229634;45.6097011;2.3636354;-0.0013869;8.0000000;0.0000000 +101.3792966;-71.3653842;45.7500601;2.3633239;-0.0017294;8.0000000;-2.9592827 +101.5792558;-71.5077541;45.8904662;2.3629441;-0.0020691;7.9256879;-5.4249199 +101.7792150;-71.6500674;46.0309325;2.3624964;-0.0024087;7.7876186;-5.4254150 +101.9791741;-71.7923129;46.1714671;2.3619812;-0.0027395;7.6470439;-5.4291430 +102.1791333;-71.9344809;46.3120792;2.3614013;-0.0030604;7.5037369;-5.4362009 +102.3790925;-72.0765640;46.4527794;2.3607573;-0.0033813;7.3574473;-5.4460851 +102.5790516;-72.2185500;46.5935739;2.3600478;-0.0037154;7.2079152;-5.4582110 +102.7790108;-72.3604326;46.7344750;2.3592715;-0.0040498;7.0548709;-5.4226721 +102.9789700;-72.5021983;46.8754913;2.3583597;-0.0058347;6.8994621;-5.3067057 +103.1789291;-72.6437967;47.0166744;2.3568526;-0.0092394;6.7439104;-5.2060120 +103.3788883;-72.7851387;47.1581236;2.3546648;-0.0126430;6.5877423;-4.7303460 +103.5788475;-72.9260704;47.2999603;2.3508928;-0.0253269;6.4425613;-4.2852183 +103.7788066;-73.0662905;47.4425175;2.3445360;-0.0382520;6.3081581;-3.9283141 +103.9787658;-73.2054188;47.5861429;2.3356601;-0.0498142;6.1823826;-3.6546721 +104.1787249;-73.3431092;47.7311426;2.3246911;-0.0599015;6.0630260;-3.4021669 +104.3786841;-73.4790551;47.8777837;2.3117028;-0.0700079;5.9497643;-3.1711278 +104.5786433;-73.6129609;48.0263419;2.2966977;-0.0800560;5.8422173;-2.9536777 +104.7786024;-73.7444378;48.1769867;2.2796773;-0.0902066;5.7402328;-2.7458639 +104.9785616;-73.8732052;48.3300140;2.2606095;-0.1005221;5.6437710;-2.5432098 +105.1785208;-73.9988785;48.4856108;2.2394507;-0.1110859;5.5529339;-2.3458982 +105.3784799;-74.1209535;48.6438158;2.2161809;-0.1218371;5.4678065;-2.1686166 +105.5784391;-74.2393340;48.8052108;2.1907573;-0.1322381;5.3879159;-1.9901160 +105.7783983;-74.3532541;48.9694650;2.1632598;-0.1429240;5.3135444;-1.8136368 +105.9783574;-74.4624855;49.1369870;2.1335926;-0.1537194;5.2448496;-1.6335473 +106.1783166;-74.5665469;49.3078422;2.1017439;-0.1647435;5.1821967;-1.4438580 +106.3782758;-74.6647424;49.4817060;2.0677159;-0.1761171;5.1261815;-1.2535121 +106.5782349;-74.7570216;49.6594298;2.0313235;-0.1874099;5.0770498;-1.0456145 +106.7781941;-74.8423908;49.8401014;1.9927085;-0.1991156;5.0356999;-0.8151303 +106.9781533;-74.9205535;50.0241499;1.9516880;-0.2112501;5.0032278;-0.5990283 +107.1781124;-74.9908872;50.2113790;1.9081734;-0.2239246;4.9792295;-0.5932956 +107.3780716;-75.0526811;50.4012856;1.8621578;-0.2369512;4.9553462;-0.5876176 +107.5780308;-75.1055071;50.5942659;1.8133534;-0.2509274;4.9315776;-0.5819941 +107.7779899;-75.1485341;50.7894172;1.7617803;-0.2651816;4.9079229;-0.5764243 +107.9779491;-75.1811524;50.9865213;1.7073022;-0.2804877;4.8843817;-0.5709078 +108.1779082;-75.2026856;51.1852274;1.6496597;-0.2961493;4.8609534;-0.5654442 +108.3778674;-75.2124269;51.3848613;1.5889153;-0.3130538;4.8376375;-0.5600328 +108.5778266;-75.2096576;51.5842192;1.5241135;-0.3366211;4.8144334;-0.5546732 +108.7777857;-75.1934172;51.7839081;1.4544635;-0.3580153;4.7913406;-0.5493649 +108.9777449;-75.1630513;51.9809958;1.3803425;-0.3883001;4.7683586;-0.5441074 +109.1777041;-75.1173737;52.1756448;1.2990208;-0.4253655;4.7454869;-0.5389002 +109.3776632;-75.0551592;52.3661480;1.2102984;-0.4480127;4.7227248;-0.5337429 +109.5776224;-74.9766536;52.5495428;1.1230336;-0.4277556;4.7000719;-0.5286349 +109.7775816;-74.8823336;52.7263196;1.0387397;-0.4146156;4.6775277;-0.5235758 +109.9775407;-74.7739223;52.8943421;0.9576209;-0.3928545;4.6550916;-0.5185651 +110.1774999;-74.6526762;53.0533038;0.8815903;-0.3680928;4.6327631;-0.5136023 +110.3774591;-74.5199514;53.2030236;0.8101139;-0.3466218;4.6105417;-0.5086871 +110.5774182;-74.3772762;53.3430868;0.7428993;-0.3258394;4.5884269;-0.5038189 +110.7773774;-74.2257808;53.4735580;0.6796826;-0.3067736;4.5664182;-0.4989973 +110.9773366;-74.0665043;53.5945377;0.6200928;-0.2889202;4.5445150;-0.4989973 +111.1772957;-73.9005408;53.7060904;0.5640714;-0.2714597;4.5225058;-0.3076088 +111.3772549;-73.7288972;53.8083965;0.5114738;-0.2551324;4.5088846;0.0675019 +111.5772141;-73.5519891;53.9019575;0.4620054;-0.2392284;4.5118772;0.3822245 +111.7771732;-73.3710405;53.9868390;0.4157438;-0.2237460;4.5287851;0.6510527 +111.9771324;-73.1863854;54.0635792;0.3724915;-0.2089094;4.5574403;0.8803363 +112.1770915;-72.9986412;54.1325557;0.3321722;-0.1942466;4.5959030;1.0887619 +112.3770507;-72.8086358;54.1941024;0.2948194;-0.1798269;4.6430314;1.2809559 +112.5770099;-72.6161233;54.2488974;0.2602537;-0.1655151;4.6978738;1.4648986 +112.7769690;-72.4221693;54.2972233;0.2286027;-0.1511700;4.7598170;1.6478077 +112.9769282;-72.2268054;54.3396755;0.1998345;-0.1363197;4.8285450;1.8441351 +113.1768874;-72.0302695;54.3768052;0.1741258;-0.1207243;4.9043195;2.0629975 +113.3768465;-71.8331116;54.4091459;0.1515683;-0.1050746;4.9877230;2.2910841 +113.5768057;-71.6350416;54.4373812;0.1321726;-0.0887596;5.0787427;2.5479853 +113.7767649;-71.4366558;54.4620772;0.1160710;-0.0723066;5.1780897;2.8243942 +113.9767240;-71.2379284;54.4838999;0.1031370;-0.0586206;5.2860326;3.0438751 +114.1766832;-71.0388993;54.5033911;0.0924485;-0.0482623;5.3999483;3.1881908 +114.3766424;-70.8397827;54.5209530;0.0838411;-0.0378521;5.5167434;3.3542803 +114.5766015;-70.6404417;54.5369594;0.0764344;-0.0366614;5.6370112;3.2487928 +114.7765607;-70.4410240;54.5515014;0.0691777;-0.0359224;5.7510997;3.1371688 +114.9765199;-70.2415092;54.5646114;0.0620927;-0.0346721;5.8591603;3.0506776 +115.1764790;-70.0418932;54.5763399;0.0553455;-0.0328123;5.9623637;2.9934135 +115.3764382;-69.8422108;54.5867582;0.0489706;-0.0309514;6.0619223;2.9438120 +115.5763974;-69.6424596;54.5959397;0.0429485;-0.0292907;6.1582616;2.8937406 +115.7763565;-69.4426619;54.6039509;0.0372565;-0.0276417;6.2515155;2.8497005 +115.9763157;-69.2428221;54.6108576;0.0318932;-0.0260113;6.3420102;2.8109920 +116.1762748;-69.0429474;54.6167249;0.0268530;-0.0244013;6.4300280;2.7771467 +116.3762340;-68.8430528;54.6216167;0.0221348;-0.0227913;6.5158186;2.7486686 +116.5761932;-68.6431297;54.6255963;0.0177175;-0.0213993;6.5996315;2.7157779 +116.7761523;-68.4431962;54.6287204;0.0135767;-0.0200180;6.6814089;2.6870692 +116.9761115;-68.2432516;54.6310436;0.0096967;-0.0189739;6.7613485;2.6473568 +117.1760707;-68.0432977;54.6326075;0.0059666;-0.0183343;6.8391929;2.5926836 +117.3760298;-67.8433432;54.6334383;0.0023645;-0.0176944;6.9145803;2.5415203 +117.5759890;-67.6433834;54.6335595;6.2820427;-0.0173994;6.9876907;2.4768275 +117.7759482;-67.4434256;54.6329851;6.2785914;-0.0171203;7.0582116;2.4143052 +117.9759073;-67.2434712;54.6317260;6.2751927;-0.0169127;7.1262806;2.3509534 +118.1758665;-67.0435216;54.6297905;6.2718231;-0.0167906;7.1919444;2.2858204 +118.3758257;-66.8435792;54.6271838;6.2684778;-0.0166686;7.2552192;2.2231671 +118.5757848;-66.6436469;54.6239107;6.2651589;-0.0165260;7.3162348;2.1639959 +118.7757440;-66.4437265;54.6199770;6.2618688;-0.0163827;7.3751416;2.1071242 +118.9757032;-66.2438198;54.6153884;6.2586073;-0.0162369;7.4320516;2.0525545 +119.1756623;-66.0439291;54.6101508;6.2553755;-0.0160880;7.4870719;2.0002289 +119.3756215;-65.8440570;54.6042702;6.2521734;-0.0159393;7.5403033;1.9498716 +119.5755807;-65.6442039;54.5977526;6.2490010;-0.0157914;7.5918353;1.9013628 +119.7755398;-65.4443728;54.5906039;6.2458581;-0.0156435;7.6417506;1.8546588 +119.9754990;-65.2445649;54.5828303;6.2427449;-0.0154945;7.6901277;1.8097607 +120.1754581;-65.0447819;54.5744375;6.2396617;-0.0153441;7.7370421;1.7666064 +120.3754173;-64.8450259;54.5654319;6.2366085;-0.0151938;7.7825651;1.7250340 +120.5753765;-64.6452977;54.5558194;6.2335855;-0.0150423;7.8267613;1.6850691 +120.7753356;-64.4455997;54.5456062;6.2305928;-0.0148908;7.8696939;1.6465643 +120.9752948;-64.2459330;54.5347985;6.2276304;-0.0147387;7.9114204;1.6095076 +121.1752540;-64.0462988;54.5234023;6.2246986;-0.0145857;7.9519963;1.5738536 +121.3752131;-63.8466990;54.5114240;6.2217973;-0.0144329;7.9914741;0.3409253 +121.5751723;-63.6471342;54.4988696;6.2189268;-0.0142787;8.0000000;0.0000000 +121.7751315;-63.4476063;54.4857456;6.2160870;-0.0141246;8.0000000;0.0000000 +121.9750906;-63.2481162;54.4720580;6.2132781;-0.0139700;8.0000000;0.0000000 +122.1750498;-63.0486650;54.4578133;6.2105002;-0.0138146;8.0000000;0.0000000 +122.3750090;-62.8492544;54.4430176;6.2077533;-0.0136594;8.0000000;0.0000000 +122.5749681;-62.6498842;54.4276774;6.2050377;-0.0135029;8.0000000;0.0000000 +122.7749273;-62.4505567;54.4117989;6.2023533;-0.0133465;8.0000000;0.0000000 +122.9748865;-62.2512721;54.3953885;6.1997002;-0.0131895;8.0000000;0.0000000 +123.1748456;-62.0520313;54.3784525;6.1970786;-0.0130318;8.0000000;0.0000000 +123.3748048;-61.8528359;54.3609975;6.1944885;-0.0128742;8.0000000;0.0000000 +123.5747640;-61.6536853;54.3430297;6.1919301;-0.0127154;8.0000000;0.0000000 +123.7747231;-61.4545815;54.3245557;6.1894034;-0.0125566;8.0000000;0.0000000 +123.9746823;-61.2555247;54.3055817;6.1869085;-0.0123972;8.0000000;0.0000000 +124.1746414;-61.0565152;54.2861144;6.1844456;-0.0122371;8.0000000;0.0000000 +124.3746006;-60.8575547;54.2661603;6.1820147;-0.0120771;8.0000000;0.0000000 +124.5745598;-60.6586420;54.2457256;6.1796159;-0.0119157;8.0000000;0.0000000 +124.7745189;-60.4597792;54.2248171;6.1772494;-0.0117544;8.0000000;0.0000000 +124.9744781;-60.2609659;54.2034413;6.1749151;-0.0115924;8.0000000;0.0000000 +125.1744373;-60.0622025;54.1816046;6.1726134;-0.0114297;8.0000000;0.0000000 +125.3743964;-59.8634902;54.1593138;6.1703442;-0.0112671;8.0000000;0.0000000 +125.5743556;-59.6648276;54.1365753;6.1681076;-0.0111030;8.0000000;0.0000000 +125.7743148;-59.4662167;54.1133958;6.1659039;-0.0109389;8.0000000;0.0000000 +125.9742739;-59.2676568;54.0897820;6.1637330;-0.0107741;8.0000000;0.0000000 +126.1742331;-59.0691480;54.0657404;6.1615951;-0.0106085;8.0000000;0.0000000 +126.3741923;-58.8706915;54.0412779;6.1594904;-0.0104430;8.0000000;0.0000000 +126.5741514;-58.6722852;54.0164008;6.1574190;-0.0102757;8.0000000;0.0000000 +126.7741106;-58.4739313;53.9911163;6.1553810;-0.0101084;8.0000000;0.0000000 +126.9740698;-58.2756288;53.9654309;6.1533765;-0.0099406;8.0000000;0.0000000 +127.1740289;-58.0773775;53.9393513;6.1514056;-0.0097721;8.0000000;0.0000000 +127.3739881;-57.8791782;53.9128845;6.1494685;-0.0096036;8.0000000;0.0000000 +127.5739473;-57.6810290;53.8860370;6.1475650;-0.0094352;8.0000000;0.0000000 +127.7739064;-57.4829316;53.8588157;6.1456951;-0.0092668;8.0000000;0.0000000 +127.9738656;-57.2848847;53.8312275;6.1438590;-0.0090987;8.0000000;0.0000000 +128.1738247;-57.0868882;53.8032789;6.1420564;-0.0089308;8.0000000;0.0000000 +128.3737839;-56.8889428;53.7749769;6.1402874;-0.0087630;8.0000000;0.0000000 +128.5737431;-56.6910461;53.7463280;6.1385519;-0.0085951;8.0000000;0.0000000 +128.7737022;-56.4931996;53.7173391;6.1368500;-0.0084273;8.0000000;0.0000000 +128.9736614;-56.2954021;53.6880167;6.1351817;-0.0082595;8.0000000;0.0000000 +129.1736206;-56.0976530;53.6583678;6.1335469;-0.0080917;8.0000000;0.0000000 +129.3735797;-55.8999530;53.6283990;6.1319457;-0.0079239;8.0000000;0.0000000 +129.5735389;-55.7022995;53.5981168;6.1303779;-0.0077566;8.0000000;0.0000000 +129.7734981;-55.5046941;53.5675282;6.1288437;-0.0075892;8.0000000;0.0000000 +129.9734572;-55.3071351;53.5366398;6.1273429;-0.0074220;8.0000000;0.0000000 +130.1734164;-55.1096220;53.5054582;6.1258755;-0.0072550;8.0000000;0.0000000 +130.3733756;-54.9121550;53.4739902;6.1244415;-0.0070879;8.0000000;0.0000000 +130.5733347;-54.7147317;53.4422421;6.1230408;-0.0069212;8.0000000;0.0000000 +130.7732939;-54.5173533;53.4102210;6.1216736;-0.0067544;8.0000000;0.0000000 +130.9732531;-54.3200182;53.3779333;6.1203396;-0.0065878;8.0000000;0.0000000 +131.1732122;-54.1227255;53.3453857;6.1190390;-0.0064214;8.0000000;0.0000000 +131.3731714;-53.9254756;53.3125849;6.1177716;-0.0062549;8.0000000;0.0000000 +131.5731305;-53.7282657;53.2795372;6.1165375;-0.0060888;8.0000000;0.0000000 +131.7730897;-53.5310970;53.2462495;6.1153366;-0.0059227;8.0000000;0.0000000 +131.9730489;-53.3339676;53.2127284;6.1141689;-0.0057568;8.0000000;0.0000000 +132.1730080;-53.1368767;53.1789803;6.1130343;-0.0055910;8.0000000;0.0000000 +132.3729672;-52.9398244;53.1450120;6.1119329;-0.0054252;8.0000000;0.0000000 +132.5729264;-52.7428081;53.1108298;6.1108646;-0.0052598;8.0000000;0.0000000 +132.7728855;-52.5458285;53.0764405;6.1098294;-0.0050944;8.0000000;0.0000000 +132.9728447;-52.3488838;53.0418506;6.1088273;-0.0049292;8.0000000;0.0000000 +133.1728039;-52.1519732;53.0070665;6.1078581;-0.0047642;8.0000000;0.0000000 +133.3727630;-51.9550964;52.9720949;6.1069220;-0.0045992;8.0000000;0.0000000 +133.5727222;-51.7582509;52.9369422;6.1060188;-0.0044346;8.0000000;0.0000000 +133.7726814;-51.5614374;52.9016150;6.1051485;-0.0042700;8.0000000;0.0000000 +133.9726405;-51.3646538;52.8661198;6.1043112;-0.0041056;8.0000000;0.0000000 +134.1725997;-51.1678994;52.8304630;6.1035066;-0.0039414;8.0000000;0.0000000 +134.3725589;-50.9711737;52.7946512;6.1027349;-0.0037772;8.0000000;0.0000000 +134.5725180;-50.7744742;52.7586907;6.1019960;-0.0036135;8.0000000;0.0000000 +134.7724772;-50.5778013;52.7225882;6.1012898;-0.0034498;8.0000000;0.0000000 +134.9724364;-50.3811533;52.6863500;6.1006163;-0.0032863;8.0000000;0.0000000 +135.1723955;-50.1845289;52.6499826;6.0999755;-0.0031231;8.0000000;0.0000000 +135.3723547;-49.9879279;52.6134925;6.0993674;-0.0029599;8.0000000;0.0000000 +135.5723138;-49.7913476;52.5768859;6.0987918;-0.0027971;8.0000000;0.0000000 +135.7722730;-49.5947885;52.5401694;6.0982487;-0.0026344;8.0000000;0.0000000 +135.9722322;-49.3982485;52.5033494;6.0977382;-0.0024719;8.0000000;0.0000000 +136.1721913;-49.2017267;52.4664322;6.0972602;-0.0023096;8.0000000;0.0000000 +136.3721505;-49.0052224;52.4294244;6.0968146;-0.0021474;8.0000000;0.0000000 +136.5721097;-48.8087332;52.3923320;6.0964013;-0.0019857;8.0000000;0.0000000 +136.7720688;-48.6122594;52.3551617;6.0960205;-0.0018240;8.0000000;0.0000000 +136.9720280;-48.4157989;52.3179197;6.0956719;-0.0016626;8.0000000;0.0000000 +137.1719872;-48.2193507;52.2806124;6.0953556;-0.0015014;8.0000000;0.0000000 +137.3719463;-48.0229143;52.2432463;6.0950714;-0.0013402;8.0000000;0.0000000 +137.5719055;-47.8264871;52.2058273;6.0948195;-0.0011796;8.0000000;0.0000000 +137.7718647;-47.6300693;52.1683621;6.0945997;-0.0010190;8.0000000;0.0000000 +137.9718238;-47.4336589;52.1308568;6.0944120;-0.0008586;8.0000000;0.0000000 +138.1717830;-47.2372548;52.0933178;6.0942563;-0.0006986;8.0000000;0.0000000 +138.3717422;-47.0408566;52.0557515;6.0941326;-0.0005385;8.0000000;0.0000000 +138.5717013;-46.8444615;52.0181639;6.0940409;-0.0003790;8.0000000;0.0000000 +138.7716605;-46.6480699;51.9805614;6.0939810;-0.0002195;8.0000000;0.0000000 +138.9716197;-46.4516798;51.9429504;6.0939531;-0.0000604;8.0000000;0.0000000 +139.1715788;-46.2552900;51.9053369;6.0939569;0.0000986;8.0000000;0.0000000 +139.3715380;-46.0589001;51.8677274;6.0939925;0.0002575;8.0000000;0.0000000 +139.5714971;-45.8625072;51.8301279;6.0940598;0.0004158;8.0000000;0.0000000 +139.7714563;-45.6661120;51.7925448;6.0941588;0.0005742;8.0000000;0.0000000 +139.9714155;-45.4697121;51.7549842;6.0942894;0.0007322;8.0000000;0.0000000 +140.1713746;-45.2733067;51.7174523;6.0944516;0.0008900;8.0000000;0.0000000 +140.3713338;-45.0768953;51.6799556;6.0946453;0.0010478;8.0000000;0.0000000 +140.5712930;-44.8804749;51.6424997;6.0948706;0.0012050;8.0000000;0.0000000 +140.7712521;-44.6840463;51.6050914;6.0951272;0.0013622;8.0000000;0.0000000 +140.9712113;-44.4876073;51.5677365;6.0954153;0.0015191;8.0000000;0.0000000 +141.1711705;-44.2911567;51.5304412;6.0957347;0.0016757;8.0000000;0.0000000 +141.3711296;-44.0946945;51.4932119;6.0960854;0.0018323;8.0000000;0.0000000 +141.5710888;-43.8982174;51.4560544;6.0964674;0.0019884;8.0000000;0.0000000 +141.7710480;-43.7017265;51.4189751;6.0968806;0.0021445;8.0000000;0.0000000 +141.9710071;-43.5052193;51.3819801;6.0973250;0.0023002;8.0000000;0.0000000 +142.1709663;-43.3086950;51.3450754;6.0978005;0.0024558;8.0000000;0.0000000 +142.3709255;-43.1121535;51.3082674;6.0983071;0.0026113;8.0000000;0.0000000 +142.5708846;-42.9155914;51.2715617;6.0988448;0.0027663;8.0000000;0.0000000 +142.7708438;-42.7190100;51.2349650;6.0994134;0.0029212;8.0000000;0.0000000 +142.9708030;-42.5224070;51.1984830;6.1000130;0.0030760;8.0000000;0.0000000 +143.1707621;-42.3257813;51.1621220;6.1006435;0.0032304;8.0000000;0.0000000 +143.3707213;-42.1291333;51.1258881;6.1013049;0.0033849;8.0000000;0.0000000 +143.5706804;-41.9324591;51.0897870;6.1019971;0.0035388;8.0000000;0.0000000 +143.7706396;-41.7357606;51.0538254;6.1027202;0.0036928;8.0000000;0.0000000 +143.9705988;-41.5390352;51.0180089;6.1034739;0.0038465;8.0000000;0.0000000 +144.1705579;-41.3422821;50.9823437;6.1042584;0.0039999;8.0000000;0.0000000 +144.3705171;-41.1455018;50.9468361;6.1050736;0.0041534;8.0000000;0.0000000 +144.5704763;-40.9486901;50.9114916;6.1059194;0.0043064;8.0000000;0.0000000 +144.7704354;-40.7518495;50.8763169;6.1067958;0.0044595;8.0000000;0.0000000 +144.9703946;-40.5549770;50.8413175;6.1077028;0.0046123;8.0000000;0.0000000 +145.1703538;-40.3580722;50.8064998;6.1086403;0.0047649;8.0000000;0.0000000 +145.3703129;-40.1611356;50.7718699;6.1096084;0.0049175;8.0000000;0.0000000 +145.5702721;-39.9641629;50.7374332;6.1106069;0.0050698;8.0000000;0.0000000 +145.7702313;-39.7671570;50.7031966;6.1116359;0.0052220;8.0000000;0.0000000 +145.9701904;-39.5701149;50.6691656;6.1126953;0.0053740;8.0000000;0.0000000 +146.1701496;-39.3730361;50.6353463;6.1137850;0.0055259;8.0000000;0.0000000 +146.3701088;-39.1759215;50.6017450;6.1149052;0.0056778;8.0000000;0.0000000 +146.5700679;-38.9787665;50.5683671;6.1160557;0.0058293;8.0000000;0.0000000 +146.7700271;-38.7815745;50.5352194;6.1172364;0.0059809;8.0000000;0.0000000 +146.9699863;-38.5843424;50.5023074;6.1184475;0.0061324;8.0000000;0.0000000 +147.1699454;-38.3870698;50.4696373;6.1196889;0.0062837;8.0000000;0.0000000 +147.3699046;-38.1897579;50.4372153;6.1209605;0.0064350;8.0000000;0.0000000 +147.5698637;-37.9924020;50.4050468;6.1222623;0.0065861;8.0000000;0.0000000 +147.7698229;-37.7950057;50.3731385;6.1235944;0.0067373;8.0000000;0.0000000 +147.9697821;-37.5975658;50.3414961;6.1249567;0.0068883;8.0000000;0.0000000 +148.1697412;-37.4000824;50.3101257;6.1263492;0.0070392;8.0000000;0.0000000 +148.3697004;-37.2025566;50.2790334;6.1277718;0.0071902;8.0000000;0.0000000 +148.5696596;-37.0049838;50.2482249;6.1292246;0.0073413;8.0000000;0.0000000 +148.7696187;-36.8073679;50.2177066;6.1307077;0.0074924;8.0000000;0.0000000 +148.9695779;-36.6097057;50.1874844;6.1322210;0.0076443;8.0000000;0.0000000 +149.1695371;-36.4119974;50.1575643;6.1337648;0.0077969;8.0000000;0.0000000 +149.3694962;-36.2142441;50.1279527;6.1353391;0.0079496;8.0000000;0.0000000 +149.5694554;-36.0164418;50.0986551;6.1369442;0.0081041;8.0000000;0.0000000 +149.7694146;-35.8185939;50.0696784;6.1385801;0.0082587;8.0000000;0.0000000 +149.9693737;-35.6206977;50.0410283;6.1402471;0.0084143;8.0000000;0.0000000 +150.1693329;-35.4227535;50.0127113;6.1419452;0.0085706;8.0000000;0.0000000 +150.3692921;-35.2247623;49.9847336;6.1436746;0.0087270;8.0000000;0.0000000 +150.5692512;-35.0267205;49.9571013;6.1454354;0.0088850;8.0000000;0.0000000 +150.7692104;-34.8286316;49.9298210;6.1472279;0.0090431;8.0000000;0.0000000 +150.9691696;-34.6304930;49.9028990;6.1490520;0.0092020;8.0000000;0.0000000 +151.1691287;-34.4323052;49.8763415;6.1509080;0.0093617;8.0000000;0.0000000 +151.3690879;-34.2340689;49.8501552;6.1527959;0.0095215;8.0000000;0.0000000 +151.5690470;-34.0357815;49.8243462;6.1547159;0.0096826;8.0000000;0.0000000 +151.7690062;-33.8374458;49.7989213;6.1566681;0.0098438;8.0000000;0.0000000 +151.9689654;-33.6390598;49.7738867;6.1586527;0.0100059;8.0000000;0.0000000 +152.1689245;-33.4406242;49.7492492;6.1606697;0.0101686;8.0000000;0.0000000 +152.3688837;-33.2421398;49.7250152;6.1627193;0.0103315;8.0000000;0.0000000 +152.5688429;-33.0436044;49.7011913;6.1648016;0.0104957;8.0000000;0.0000000 +152.7688020;-32.8450203;49.6777841;6.1669167;0.0106598;8.0000000;0.0000000 +152.9687612;-32.6463864;49.6548003;6.1690647;0.0108247;8.0000000;0.0000000 +153.1687204;-32.4477032;49.6322464;6.1712457;0.0109900;8.0000000;0.0000000 +153.3686795;-32.2489715;49.6101293;6.1734598;0.0111555;8.0000000;0.0000000 +153.5686387;-32.0501900;49.5884554;6.1757071;0.0113219;8.0000000;0.0000000 +153.7685979;-31.8513607;49.5672317;6.1779876;0.0114883;8.0000000;0.0000000 +153.9685570;-31.6524829;49.5464648;6.1803015;0.0116556;8.0000000;0.0000000 +154.1685162;-31.4535572;49.5261614;6.1826490;0.0118237;8.0000000;0.0000000 +154.3684754;-31.2545843;49.5063284;6.1850300;0.0119917;8.0000000;0.0000000 +154.5684345;-31.0555640;49.4869726;6.1874445;0.0121586;8.0000000;0.0000000 +154.7683937;-30.8564975;49.4681007;6.1898925;0.0123255;8.0000000;0.0000000 +154.9683529;-30.6573851;49.4497194;6.1923722;0.0124671;8.0000000;0.0000000 +155.1683120;-30.4582275;49.4318345;6.1948776;0.0125919;8.0000000;0.0000000 +155.3682712;-30.2590256;49.4144511;6.1974079;0.0127082;8.0000000;0.0000000 +155.5682303;-30.0597810;49.3975737;6.1999534;0.0127528;8.0000000;0.0000000 +155.7681895;-29.8604927;49.3812043;6.2025079;0.0127972;8.0000000;0.0000000 +155.9681487;-29.6611648;49.3653446;6.2050616;0.0126826;8.0000000;0.0000000 +156.1681078;-29.4617967;49.3499904;6.2075759;0.0124663;8.0000000;0.0000000 +156.3680670;-29.2623882;49.3351329;6.2100468;0.0122300;8.0000000;0.0000000 +156.5680262;-29.0629490;49.3207627;6.2124530;0.0118366;8.0000000;0.0000000 +156.7679853;-28.8634718;49.3068642;6.2147805;0.0114435;8.0000000;0.0000000 +156.9679445;-28.6639654;49.2934224;6.2170292;0.0110460;8.0000000;0.0000000 +157.1679037;-28.4644298;49.2804213;6.2191979;0.0106458;8.0000000;0.0000000 +157.3678628;-28.2648644;49.2678447;6.2212867;0.0102468;8.0000000;0.0000000 +157.5678220;-28.0652776;49.2556774;6.2232965;0.0098559;8.0000000;0.0000000 +157.7677812;-27.8656643;49.2439033;6.2252282;0.0094650;8.0000000;0.0000000 +157.9677403;-27.6660307;49.2325071;6.2270817;0.0090738;8.0000000;0.0000000 +158.1676995;-27.4663766;49.2214731;6.2288570;0.0086822;8.0000000;0.0000000 +158.3676587;-27.2667017;49.2107856;6.2305539;0.0082909;8.0000000;0.0000000 +158.5676178;-27.0670127;49.2004294;6.2321727;0.0079007;8.0000000;0.0000000 +158.7675770;-26.8673047;49.1903885;6.2337136;0.0075105;8.0000000;0.0000000 +158.9675362;-26.6675834;49.1806476;6.2351764;0.0071206;8.0000000;0.0000000 +159.1674953;-26.4678482;49.1711910;6.2365612;0.0067309;8.0000000;0.0000000 +159.3674545;-26.2680989;49.1620033;6.2378682;0.0063413;8.0000000;0.0000000 +159.5674136;-26.0683410;49.1530689;6.2390973;0.0059524;8.0000000;0.0000000 +159.7673728;-25.8685701;49.1443723;6.2402487;0.0055635;8.0000000;0.0000000 +159.9673320;-25.6687911;49.1358979;6.2413223;0.0051752;8.0000000;0.0000000 +160.1672911;-25.4690032;49.1276302;6.2423183;0.0047873;8.0000000;0.0000000 +160.3672503;-25.2692058;49.1195538;6.2432368;0.0043995;8.0000000;0.0000000 +160.5672095;-25.0694042;49.1116532;6.2440779;0.0040125;8.0000000;0.0000000 +160.7671686;-24.8695940;49.1039129;6.2448415;0.0036256;8.0000000;0.0000000 +160.9671278;-24.6697796;49.0963174;6.2455278;0.0032392;8.0000000;0.0000000 +161.1670870;-24.4699601;49.0888514;6.2461369;0.0028532;8.0000000;0.0000000 +161.3670461;-24.2701349;49.0814993;6.2466689;0.0024673;8.0000000;0.0000000 +161.5670053;-24.0703087;49.0742459;6.2471237;0.0020823;8.0000000;0.0000000 +161.7669645;-23.8704773;49.0670757;6.2475016;0.0016973;8.0000000;0.0000000 +161.9669236;-23.6706447;49.0599733;6.2478025;0.0013129;8.0000000;0.0000000 +162.1668828;-23.4708100;49.0529233;6.2480267;0.0009290;8.0000000;0.0000000 +162.3668420;-23.2709728;49.0459105;6.2481741;0.0005453;8.0000000;0.0000000 +162.5668011;-23.0711370;49.0389195;6.2482449;0.0001627;8.0000000;0.0000000 +162.7667603;-22.8712991;49.0319349;6.2482391;-0.0002198;8.0000000;0.0000000 +162.9667195;-22.6714626;49.0249416;6.2481570;-0.0006016;8.0000000;0.0000000 +163.1666786;-22.4716268;49.0179243;6.2479986;-0.0009828;8.0000000;0.0000000 +163.3666378;-22.2717913;49.0108676;6.2477639;-0.0013637;8.0000000;0.0000000 +163.5665969;-22.0719596;49.0037565;6.2474534;-0.0017425;8.0000000;0.0000000 +163.7665561;-21.8721287;48.9965758;6.2470671;-0.0021213;8.0000000;0.0000000 +163.9665153;-21.6723019;48.9893103;6.2466050;-0.0025004;8.0000000;0.0000000 +164.1664744;-21.4724785;48.9819449;6.2460671;-0.0028796;8.0000000;0.0000000 +164.3664336;-21.2726586;48.9744644;6.2454534;-0.0032569;8.0000000;0.0000000 +164.5663928;-21.0728452;48.9668539;6.2447655;-0.0036234;8.0000000;0.0000000 +164.7663519;-20.8730359;48.9590985;6.2440043;-0.0039899;8.0000000;0.0000000 +164.9663111;-20.6732336;48.9511838;6.2431687;-0.0043749;8.0000000;0.0000000 +165.1662703;-20.4734382;48.9430942;6.2422544;-0.0047699;8.0000000;0.0000000 +165.3662294;-20.2736497;48.9348140;6.2412599;-0.0052402;8.0000000;-3.0247383 +165.5661886;-20.0738705;48.9263225;6.2401235;-0.0061261;7.9240363;-5.1449641 +165.7661478;-19.8741024;48.9175864;6.2388100;-0.0070121;7.7931243;-5.0137339 +165.9661069;-19.6743491;48.9085648;6.2371969;-0.0097656;7.6634002;-4.8374359 +166.1660661;-19.4746131;48.8991525;6.2348708;-0.0135000;7.5361212;-4.6407788 +166.3660253;-19.2749010;48.8892008;6.2317884;-0.0178495;7.4119627;-4.2806281 +166.5659844;-19.0752364;48.8785212;6.2274539;-0.0255065;7.2955664;-3.9419431 +166.7659436;-18.8756147;48.8668227;6.2215883;-0.0331588;7.1867123;-3.6521395 +166.9659027;-18.6760814;48.8538029;6.2142324;-0.0402145;7.0843684;-3.3921378 +167.1658619;-18.4766573;48.8391792;6.2055156;-0.0469720;6.9879681;-3.1477570 +167.3658211;-18.2773717;48.8226824;6.1954475;-0.0536655;6.8973076;-2.9311468 +167.5657802;-18.0782710;48.8040493;6.1840830;-0.0600005;6.8118010;-2.7219126 +167.7657394;-17.8794273;48.7830308;6.1714499;-0.0663660;6.7314256;-2.5194745 +167.9656986;-17.6808493;48.7593716;6.1575400;-0.0727444;6.6561630;-2.3211056 +168.1656577;-17.4826529;48.7328283;6.1423524;-0.0791653;6.5860651;-2.1251565 +168.3656169;-17.2849354;48.7031561;6.1258786;-0.0856347;6.5212241;-1.9290099 +168.5655761;-17.0876748;48.6700888;6.1080972;-0.0921795;6.4618045;-1.7312864 +168.7655352;-16.8911504;48.6334084;6.0890082;-0.0987966;6.4080063;-1.5295603 +168.9654944;-16.6953155;48.5928376;6.0685806;-0.1055044;6.3600979;-1.3212395 +169.1654536;-16.5004062;48.5481497;6.0468029;-0.1123211;6.3184221;-1.1051191 +169.3654127;-16.3066161;48.4991129;6.0236614;-0.1192262;6.2833510;-0.9447773 +169.5653719;-16.1139202;48.4454334;5.9991068;-0.1262965;6.2532125;-0.9357357 +169.7653311;-15.9227738;48.3869451;5.9731433;-0.1334853;6.2232185;-0.9267806 +169.9652902;-15.7331649;48.3233452;5.9457149;-0.1408467;6.1933684;-0.9179111 +170.1652494;-15.5454531;48.2544413;5.9167985;-0.1483897;6.1636615;-0.9091266 +170.3652086;-15.3599348;48.1800260;5.8863723;-0.1560799;6.1340970;-0.9004261 +170.5651677;-15.1767179;48.0998081;5.8543554;-0.1640927;6.1046744;-0.8918089 +170.7651269;-14.9963318;48.0136702;5.8207390;-0.1722460;6.0753929;-0.8832742 +170.9650860;-14.8189650;47.9213433;5.7854574;-0.1807157;6.0462518;-0.8748212 +171.1650452;-14.6450622;47.8226751;5.7484489;-0.1894827;6.0172505;-0.8664490 +171.3650044;-14.4750506;47.7175084;5.7096775;-0.1984653;5.9883884;-0.8581570 +171.5649635;-14.3093249;47.6056645;5.6690506;-0.2079512;5.9596646;-0.8499443 +171.7649227;-14.1483817;47.4870199;5.6265027;-0.2176225;5.9310787;-0.8418102 +171.9648819;-13.9928154;47.3615370;5.5819966;-0.2278472;5.9026298;-0.8337540 +172.1648410;-13.8430765;47.2290570;5.5353799;-0.2384636;5.8743174;-0.8257748 +172.3648002;-13.6998175;47.0895855;5.4866259;-0.2493019;5.8461409;-0.8178720 +172.5647594;-13.5637940;46.9432671;5.4356731;-0.2607745;5.8180994;-0.8100449 +172.7647185;-13.4353710;46.7898050;5.3823262;-0.2723222;5.7901925;-0.8022927 +172.9646777;-13.3157367;46.6299068;5.3267161;-0.2848572;5.7624194;-0.7946146 +173.1646369;-13.2052588;46.4632512;5.2684064;-0.2984055;5.7347796;-0.7870100 +173.3645960;-13.1048514;46.2901874;5.2074753;-0.3066021;5.7072723;-0.7794782 +173.5645552;-13.0153459;46.1116016;5.1466270;-0.3028513;5.6798969;-0.7720185 +173.7645144;-12.9366628;45.9275542;5.0862074;-0.3011005;5.6526529;-0.7646302 +173.9644735;-12.8692659;45.7393942;5.0268694;-0.2905110;5.6255395;-0.7573126 +174.1644327;-12.8128849;45.5475589;4.9700282;-0.2781829;5.5985562;-0.7500650 +174.3643919;-12.7672434;45.3527954;4.9154954;-0.2671012;5.5717024;-0.7428868 +174.5643510;-12.7320938;45.1560206;4.8631613;-0.2566020;5.5449773;-0.7357773 +174.7643102;-12.7070726;44.9575987;4.8128142;-0.2470001;5.5183804;-0.7287358 +174.9642693;-12.6918848;44.7582207;4.7643236;-0.2379776;5.4919111;-0.7217617 +175.1642285;-12.6862007;44.5583544;4.7176032;-0.2294130;5.4655688;-0.7148543 +175.3641877;-12.6896910;44.3584273;4.6725264;-0.2214921;5.4393528;-0.7080131 +175.5641468;-12.7020319;44.1588365;4.6290011;-0.2138509;5.4132625;-0.7012373 +175.7641060;-12.7228907;43.9600010;4.5869713;-0.2066537;5.3872974;-0.6945263 +175.9640652;-12.7519551;43.7621456;4.5463266;-0.1998323;5.3614569;-0.6878796 +176.1640243;-12.7888977;43.5656312;4.5070290;-0.1932570;5.3357402;-0.6878796 +176.3639835;-12.8333934;43.3707435;4.4690222;-0.1870202;5.3098991;-0.6092222 +176.5639427;-12.8851739;43.1775479;4.4322266;-0.1809185;5.2869073;-0.3757228 +176.7639018;-12.9438783;42.9864526;4.3966493;-0.1750406;5.2726778;-0.1743801 +176.9638610;-13.0092556;42.7974676;4.3622128;-0.1693663;5.2660605;0.0001761 +177.1638202;-13.0809928;42.6108118;4.3289016;-0.1638126;5.2660672;0.1541717 +177.3637793;-13.1587707;42.4266851;4.2966971;-0.1584373;5.2719180;0.2890508 +177.5637385;-13.2424042;42.2449790;4.2655391;-0.1530982;5.2828701;0.4114743 +177.7636977;-13.3315087;42.0660237;4.2354565;-0.1478727;5.2984217;0.5212271 +177.9636568;-13.4258896;41.8897349;4.2063985;-0.1427539;5.3180561;0.6203172 +178.1636160;-13.5252674;41.7162061;4.1783595;-0.1376801;5.3413291;0.7120282 +178.3635752;-13.6293371;41.5455550;4.1513390;-0.1326931;5.3679186;0.7963478 +178.5635343;-13.7379731;41.3776081;4.1252932;-0.1277367;5.3975016;0.8759963 +178.7634935;-13.8508085;41.2125710;4.1002468;-0.1228277;5.4298574;0.9513387 +178.9634526;-13.9676822;41.0503290;4.0761507;-0.1183494;5.4647789;1.0116948 +179.1634118;-14.0883702;40.8908885;4.0529016;-0.1141785;5.5016728;1.0618326 +179.3633710;-14.2126265;40.7342948;4.0304899;-0.1101835;5.5401309;1.1064785 +179.5633301;-14.3403716;40.5804155;4.0086094;-0.1086267;5.5799240;1.0756057 +179.7632893;-14.4713915;40.4293905;3.9870441;-0.1070945;5.6183366;1.0476449 +179.9632485;-14.6056255;40.2811943;3.9657760;-0.1056776;5.6554998;1.0193910 +180.1632076;-14.7429680;40.1358602;3.9447761;-0.1043624;5.6914279;0.9910946 +180.3631668;-14.8832904;39.9934469;3.9240390;-0.1030678;5.7261425;0.9652452 +180.5631260;-15.0265507;39.8539206;3.9035892;-0.1014550;5.7597507;0.9528319 +180.7630851;-15.1725892;39.7173506;3.8834615;-0.0998786;5.7927353;0.9413716 +180.9630443;-15.3213336;39.5837175;3.8636451;-0.0983211;5.8251399;0.9313194 +181.1630035;-15.4726800;39.4530314;3.8441393;-0.0967774;5.8570219;0.9227157 +181.3629626;-15.6265080;39.3253140;3.8249411;-0.0952682;5.8884393;0.9147104 +181.5629218;-15.7827700;39.2005269;3.8060375;-0.0937938;5.9194194;0.9071946 +181.7628810;-15.9413249;39.0787078;3.7874283;-0.0923484;5.9499857;0.9002856 +181.9628401;-16.1021088;38.9598323;3.7691043;-0.0909310;5.9801648;0.8939402 +182.1627993;-16.2650306;38.8438975;3.7510614;-0.0895354;6.0099812;0.8882940 +182.3627585;-16.4299854;38.7309094;3.7332966;-0.0881675;6.0394635;0.8830568 +182.5627176;-16.5969318;38.6208301;3.7158000;-0.0868243;6.0686300;0.8782705 +182.7626768;-16.7657466;38.5136770;3.6985716;-0.0855043;6.0975000;0.8739297 +182.9626359;-16.9363746;38.4094220;3.6816039;-0.0842110;6.1260923;0.8698445 +183.1625951;-17.1087366;38.3080535;3.6648924;-0.0829390;6.1544190;0.8661603 +183.3625543;-17.2827416;38.2095654;3.6484344;-0.0816892;6.1824968;0.8627950 +183.5625134;-17.4583542;38.1139205;3.6322224;-0.0804562;6.2103393;0.8599023 +183.7624726;-17.6354672;38.0211214;3.6162566;-0.0792418;6.2379648;0.8573696 +183.9624318;-17.8140339;37.9311375;3.6005310;-0.0780499;6.2653877;0.8549915 +184.1623909;-17.9939853;37.8439503;3.5850416;-0.0768762;6.2926155;0.8529033 +184.3623501;-18.1752432;37.7595454;3.5697862;-0.0757197;6.3196599;0.8511053 +184.5623093;-18.3577774;37.6778858;3.5547599;-0.0745685;6.3465324;0.8500411 +184.7622684;-18.5414954;37.5989628;3.5399635;-0.0734321;6.3732582;0.8492752 +184.9622276;-18.7263574;37.5227438;3.5253922;-0.0723134;6.3998485;0.8486547 +185.1621868;-18.9123037;37.4492051;3.5110429;-0.0712088;6.4263095;0.8482986 +185.3621459;-19.0992677;37.3783255;3.4969140;-0.0701183;6.4526509;0.8481780 +185.5621051;-19.2872235;37.3100682;3.4830006;-0.0690398;6.4788815;0.8483535 +185.7620643;-19.4760920;37.2444163;3.4693026;-0.0679730;6.5050118;0.8488101 +185.9620234;-19.6658398;37.1813359;3.4558164;-0.0669180;6.5310514;0.8495141 +186.1619826;-19.8564159;37.1207997;3.4425401;-0.0658725;6.5570092;0.8505431 +186.3619418;-20.0477640;37.0627816;3.4294723;-0.0648380;6.5828958;0.8518023 +186.5619009;-20.2398618;37.0072453;3.4166097;-0.0638118;6.6087191;0.8533924 +186.7618601;-20.4326429;36.9541672;3.4039520;-0.0627948;6.6344898;0.8552497 +186.9618192;-20.6260791;36.9035129;3.3914965;-0.0617859;6.6602166;0.8573950 +187.1617784;-20.8201271;36.8552521;3.3792421;-0.0607837;6.6859086;0.8598811 +187.3617376;-21.0147406;36.8093549;3.3671876;-0.0597899;6.7115762;0.8626003 +187.5616967;-21.2098994;36.7657853;3.3553308;-0.0588011;6.7372268;0.8656991 +187.7616559;-21.4055494;36.7245150;3.3436714;-0.0578193;6.7628718;0.8690577 +187.9616151;-21.6016666;36.6855087;3.3322075;-0.0568433;6.7885187;0.8727181 +188.1615742;-21.7982149;36.6487340;3.3209383;-0.0558720;6.8141766;0.8767180 +188.3615334;-21.9951570;36.6141583;3.3098629;-0.0549071;6.8398551;0.8809577 +188.5614926;-22.1924741;36.5817456;3.2989798;-0.0539453;6.8655611;0.8855850 +188.7614517;-22.3901243;36.5514640;3.2882888;-0.0529888;6.8913055;0.8904735 +188.9614109;-22.5880862;36.5232781;3.2777884;-0.0520367;6.9170953;0.8956599 +189.1613701;-22.7863310;36.4971534;3.2674781;-0.0510880;6.9429387;0.9011760 +189.3613292;-22.9848296;36.4730556;3.2573571;-0.0501442;6.9688446;0.9069372 +189.5612884;-23.1835637;36.4509489;3.2474244;-0.0492035;6.9948192;0.9130255 +189.7612476;-23.3825033;36.4307987;3.2376794;-0.0482668;7.0208711;0.9193858 +189.9612067;-23.5816287;36.4125694;3.2281213;-0.0473347;7.0470072;0.9259743 +190.1611659;-23.7809181;36.3962256;3.2187492;-0.0464061;7.0732330;0.9328462 +190.3611251;-23.9803500;36.3817319;3.2095625;-0.0454815;7.0995554;0.9399617 +190.5610842;-24.1799057;36.3690524;3.2005600;-0.0445623;7.1259803;0.9472432 +190.7610434;-24.3795670;36.3581515;3.1917410;-0.0436461;7.1525111;0.9548190 +190.9610025;-24.5793148;36.3489936;3.1831047;-0.0427372;7.1791549;0.9624467 +191.1609617;-24.7791342;36.3415431;3.1746494;-0.0418332;7.2059118;0.9702593 +191.3609209;-24.9790103;36.3357642;3.1663746;-0.0409331;7.2327857;0.9783019 +191.5608800;-25.1789237;36.3316215;3.1582787;-0.0400431;7.2597817;0.9862452 +191.7608392;-25.3788676;36.3290797;3.1503605;-0.0391551;7.2868956;0.9945158 +191.9607984;-25.5788223;36.3281034;3.1426193;-0.0382758;7.3141351;1.0027518 +192.1607575;-25.7787795;36.3286574;3.1350531;-0.0374018;7.3414979;1.0111381 +192.3607167;-25.9787304;36.3307070;3.1276614;-0.0365312;7.3689866;1.0197762 +192.5606759;-26.1786543;36.3342170;3.1204429;-0.0356704;7.3966067;1.0283090 +192.7606350;-26.3785547;36.3391530;3.1133961;-0.0348111;7.4243539;1.0371954 +192.9605942;-26.5784113;36.3454803;3.1065208;-0.0339591;7.4522362;1.0461099 +193.1605534;-26.7782215;36.3531645;3.0998152;-0.0331113;7.4802529;1.0552228 +193.3605125;-26.9779813;36.3621717;3.0932787;-0.0322663;7.5084077;1.0646164 +193.5604717;-27.1776696;36.3724671;3.0869107;-0.0314291;7.5367065;1.0739930 +193.7604309;-27.3772982;36.3840178;3.0807096;-0.0305932;7.5651474;1.0837400 +193.9603900;-27.5768462;36.3967891;3.0746751;-0.0297696;7.5937384;1.0932023 +194.1603492;-27.7763164;36.4107482;3.0688041;-0.0289527;7.6224703;1.1027213 +194.3603084;-27.9757080;36.4258622;3.0630961;-0.0281409;7.6513432;1.1123904 +194.5602675;-28.1750008;36.4420972;3.0575484;-0.0273495;7.6803592;1.1212936 +194.7602267;-28.3742120;36.4594227;3.0521585;-0.0265591;7.7094970;1.1306051 +194.9601858;-28.5733215;36.4778054;3.0469266;-0.0257727;7.7387656;1.1401340 +195.1601450;-28.7723355;36.4972140;3.0418515;-0.0249886;7.7681693;1.1499828 +195.3601042;-28.9712559;36.5176175;3.0369330;-0.0242057;7.7977146;1.1602116 +195.5600633;-29.1700643;36.5389823;3.0321711;-0.0234248;7.8274097;1.1707627 +195.7600225;-29.3687807;36.5612793;3.0275650;-0.0226447;7.8572611;1.1817161 +195.9599817;-29.5673873;36.5844750;3.0231149;-0.0218656;7.8872773;1.1930562 +196.1599408;-29.7658924;36.6085391;3.0188205;-0.0210872;7.9174660;1.2047974 +196.3599000;-29.9642995;36.6334407;3.0146816;-0.0203094;7.9478354;1.2169414 +196.5598592;-30.1625942;36.6591465;3.0106984;-0.0195319;7.9783937;0.8632631 +196.7598183;-30.3607960;36.6856278;3.0068704;-0.0187550;8.0000000;0.0000000 +196.9597775;-30.5588910;36.7128514;3.0031979;-0.0179780;8.0000000;0.0000000 +197.1597367;-30.7568886;36.7407872;2.9996807;-0.0172012;8.0000000;0.0000000 +197.3596958;-30.9547934;36.7694044;2.9963187;-0.0164247;8.0000000;0.0000000 +197.5596550;-31.1525949;36.7986703;2.9931122;-0.0156477;8.0000000;0.0000000 +197.7596142;-31.3503115;36.8285561;2.9900609;-0.0148711;8.0000000;0.0000000 +197.9595733;-31.5479332;36.8590289;2.9871650;-0.0140939;8.0000000;0.0000000 +198.1595325;-31.7454697;36.8900587;2.9844245;-0.0133166;8.0000000;0.0000000 +198.3594916;-31.9429263;36.9216150;2.9818394;-0.0125394;8.0000000;0.0000000 +198.5594508;-32.1402968;36.9536653;2.9794098;-0.0117616;8.0000000;0.0000000 +198.7594100;-32.3375974;36.9861806;2.9771357;-0.0109841;8.0000000;0.0000000 +198.9593691;-32.5348220;37.0191285;2.9750171;-0.0102050;8.0000000;0.0000000 +199.1593283;-32.7319801;37.0524790;2.9730545;-0.0094253;8.0000000;0.0000000 +199.3592875;-32.9290774;37.0862014;2.9712490;-0.0085855;8.0000000;0.0000000 +199.5592466;-33.1261113;37.1202602;2.9696400;-0.0075084;8.0000000;0.0000000 +199.7592058;-33.3230996;37.1546157;2.9682463;-0.0064314;8.0000000;0.0000000 +199.9591650;-33.5200383;37.1892214;2.9671167;-0.0046621;8.0000000;0.0000000 +200.1591241;-33.7169472;37.2240109;2.9663903;-0.0026034;8.0000000;0.0000000 +200.3590833;-33.9138419;37.2589035;2.9660762;-0.0005146;8.0000000;0.0000000 +200.5590425;-34.1107244;37.2938144;2.9661937;0.0016899;8.0000000;0.0000000 +200.7590016;-34.3076285;37.3286606;2.9667520;0.0038940;8.0000000;0.0000000 +200.9589608;-34.5045521;37.3633521;2.9677496;0.0060778;8.0000000;0.0000000 +201.1589200;-34.7015205;37.3978048;2.9691824;0.0082532;8.0000000;0.0000000 +201.3588791;-34.8985501;37.4319331;2.9710501;0.0104268;8.0000000;0.0000000 +201.5588383;-35.0956411;37.4656490;2.9733518;0.0125952;8.0000000;0.0000000 +201.7587975;-35.2928256;37.4988701;2.9760871;0.0147632;8.0000000;0.0000000 +201.9587566;-35.4901005;37.5315077;2.9792558;0.0169293;8.0000000;0.0000000 +202.1587158;-35.6874870;37.5634777;2.9828574;0.0190946;8.0000000;0.0000000 +202.3586749;-35.8849983;37.5946945;2.9868921;0.0212591;8.0000000;0.0000000 +202.5586341;-36.0826323;37.6250701;2.9913592;0.0234220;8.0000000;0.0000000 +202.7585933;-36.2804143;37.6545210;2.9962590;0.0255852;8.0000000;0.0000000 +202.9585524;-36.4783388;37.6829588;3.0015910;0.0277464;8.0000000;0.0000000 +203.1585116;-36.6764197;37.7102984;3.0073553;0.0299078;8.0000000;0.0000000 +203.3584708;-36.8746638;37.7364532;3.0135519;0.0320691;8.0000000;0.0000000 +203.5584299;-37.0730656;37.7613356;3.0201802;0.0342294;8.0000000;0.0000000 +203.7583891;-37.2716383;37.7848600;3.0272410;0.0363915;8.0000000;0.0000000 +203.9583483;-37.4703736;37.8069385;3.0347338;0.0385520;8.0000000;0.0000000 +204.1583074;-37.6692739;37.8274844;3.0426588;0.0407145;8.0000000;0.0000000 +204.3582666;-37.8683368;37.8464105;3.0510164;0.0428782;8.0000000;0.0000000 +204.5582258;-38.0675517;37.8636290;3.0598065;0.0450419;8.0000000;0.0000000 +204.7581849;-38.2669154;37.8790526;3.0690298;0.0472099;8.0000000;0.0000000 +204.9581441;-38.4664155;37.8925936;3.0786866;0.0493770;8.0000000;0.0000000 +205.1581033;-38.6660391;37.9041641;3.0887770;0.0515488;8.0000000;0.0000000 +205.3580624;-38.8657712;37.9136764;3.0993022;0.0537241;8.0000000;0.0000000 +205.5580216;-39.0655956;37.9210426;3.1102624;0.0559008;8.0000000;0.0000000 +205.7579808;-39.2654864;37.9261746;3.1216586;0.0580861;8.0000000;0.0000000 +205.9579399;-39.4654275;37.9289847;3.1334923;0.0602731;8.0000000;0.0000000 +206.1578991;-39.6653856;37.9293848;3.1457639;0.0624697;8.0000000;0.0000000 +206.3578582;-39.8653302;37.9272873;3.1584756;0.0646741;8.0000000;0.0000000 +206.5578174;-40.0652387;37.9226040;3.1716288;0.0668843;8.0000000;0.0000000 +206.7577766;-40.2650564;37.9152480;3.1852248;0.0691090;8.0000000;0.0000000 +206.9577357;-40.4647633;37.9051309;3.1992671;0.0713393;8.0000000;0.0000000 +207.1576949;-40.6643009;37.8921664;3.2137564;0.0735857;8.0000000;0.0000000 +207.3576541;-40.8636199;37.8762678;3.2286961;0.0758459;8.0000000;0.0000000 +207.5576132;-41.0626898;37.8573468;3.2440897;0.0781178;8.0000000;0.0000000 +207.7575724;-41.2614217;37.8353206;3.2599385;0.0804126;8.0000000;0.0000000 +207.9575316;-41.4597901;37.8100998;3.2762488;0.0827188;8.0000000;0.0000000 +208.1574907;-41.6577070;37.7816024;3.2930219;0.0850506;8.0000000;0.0000000 +208.3574499;-41.8551009;37.7497450;3.3102630;0.0874042;8.0000000;0.0000000 +208.5574091;-42.0519304;37.7144384;3.3279784;0.0897785;8.0000000;0.0000000 +208.7573682;-42.2480679;37.6756095;3.3461695;0.0921866;8.0000000;0.0000000 +208.9573274;-42.4434793;37.6331667;3.3648466;0.0946159;8.0000000;0.0000000 +209.1572866;-42.6380428;37.5870368;3.3840121;0.0970834;8.0000000;0.0000000 +209.3572457;-42.8316613;37.5371422;3.4036733;0.0995835;8.0000000;0.0000000 +209.5572049;-43.0242770;37.4833940;3.4238403;0.1021183;8.0000000;0.0000000 +209.7571641;-43.2157216;37.4257340;3.4445156;0.1047012;8.0000000;0.0000000 +209.9571232;-43.4059459;37.3640695;3.4657141;0.1073186;8.0000000;0.0000000 +210.1570824;-43.5947907;37.2983413;3.4874399;0.1099920;8.0000000;0.0000000 +210.3570415;-43.7821295;37.2284815;3.5097038;0.1127139;8.0000000;0.0000000 +210.5570007;-43.9678793;37.1544041;3.5325207;0.1154899;8.0000000;0.0000000 +210.7569599;-44.1518308;37.0760733;3.5558948;0.1183323;8.0000000;0.0000000 +210.9569190;-44.3339100;36.9933973;3.5798472;0.1212327;8.0000000;0.0000000 +211.1568782;-44.5139172;36.9063386;3.6043856;0.1242143;8.0000000;-0.8264465 +211.3568374;-44.6916922;36.8148437;3.6295255;0.1272667;7.9793163;-1.5236253 +211.5567965;-44.8671139;36.7188367;3.6552890;0.1304102;7.9410430;-1.5090440 +211.7567557;-45.0399348;36.6183102;3.6816848;0.1336444;7.9029532;-1.4946023 +211.9567149;-45.2100394;36.5131819;3.7087420;0.1369845;7.8650461;-1.4802987 +212.1566740;-45.3771866;36.4034430;3.7364774;0.1404441;7.8273208;-1.4661321 +212.3566332;-45.5411746;36.2890621;3.7649130;0.1440270;7.7897765;-1.4521010 +212.5565924;-45.7018264;36.1699867;3.7940914;0.1478141;7.7524123;-1.4382042 +212.7565515;-45.8588590;36.0462388;3.8240345;0.1517256;7.7152273;-1.4244404 +212.9565107;-46.0120911;35.9177619;3.8547876;0.1559064;7.6782207;-1.4108083 +213.1564699;-46.1612314;35.7845815;3.8863990;0.1603007;7.6413915;-1.3973066 +213.3564290;-46.3060201;35.6466958;3.9189015;0.1648127;7.6047390;-1.3839342 +213.5563882;-46.4462054;35.5040945;3.9523222;0.1694699;7.5682624;-1.3706898 +213.7563474;-46.5814520;35.3568538;3.9866885;0.1743287;7.5319607;-1.3575721 +213.9563065;-46.7115045;35.2049801;4.0218714;0.1771872;7.4958331;-1.3445799 +214.1562657;-46.8360927;35.0485982;4.0575491;0.1796952;7.4598788;-0.8431659 +214.3562248;-46.9549769;34.8878515;4.0936780;0.1804197;7.4372437;-1.3236429 +214.5561840;-47.0679939;34.7229313;4.1294344;0.1772826;7.4015704;-1.3109755 +214.7561432;-47.1751189;34.5540699;4.1645910;0.1743464;7.3660682;-1.2984293 +214.9561023;-47.2762711;34.3816272;4.1990469;0.1701169;7.3307364;-1.2860031 +215.1560615;-47.3715167;34.2058129;4.2326278;0.1657861;7.2955740;-1.2736959 +215.3560207;-47.4608852;34.0269310;4.2653647;0.1616334;7.2605802;-1.2615064 +215.5559798;-47.5444125;33.8452852;4.2972713;0.1575548;7.2257543;-1.2494337 +215.7559390;-47.6221964;33.6610496;4.3283861;0.1536380;7.1910955;-1.2374764 +215.9558982;-47.6942629;33.4745656;4.3587263;0.1498871;7.1566029;-1.2256336 +216.1558573;-47.7607199;33.2859740;4.3883343;0.1462672;7.1222757;-1.2139041 +216.3558165;-47.8216342;33.0955145;4.4172335;0.1427803;7.0881132;-1.2022869 +216.5557757;-47.8770787;32.9034209;4.4454391;0.1393760;7.0541146;-1.1907808 +216.7557348;-47.9271601;32.7098111;4.4729820;0.1360901;7.0202790;-1.1793849 +216.9556940;-47.9719428;32.5149619;4.4998703;0.1328914;6.9866057;-1.1680980 +217.1556532;-48.0115386;32.3189618;4.5261313;0.1297808;6.9530940;-1.1569192 +217.3556123;-48.0460352;32.1219974;4.5517808;0.1267650;6.9197430;-1.1458473 +217.5555715;-48.0755251;31.9242445;4.5768303;0.1238119;6.8865519;-1.1348814 +217.7555307;-48.1001152;31.7257824;4.6013024;0.1209431;6.8535201;-1.1240204 +217.9554898;-48.1198941;31.5268297;4.6252025;0.1181406;6.8206467;-1.1132634 +218.1554490;-48.1349701;31.3274385;4.6485514;0.1154010;6.7879310;-1.1026093 +218.3554081;-48.1454411;31.1277511;4.6713599;0.1127326;6.7553722;-1.0920572 +218.5553673;-48.1514078;30.9278970;4.6936380;0.1101158;6.7229695;-1.0816060 +218.7553265;-48.1529728;30.7279259;4.7154023;0.1075589;6.6907223;-1.0816060 +218.9552856;-48.1502373;30.5280074;4.7366571;0.1050584;6.6583189;-1.0578907 +219.1552448;-48.1433021;30.3281672;4.7574187;0.1026037;6.6264728;-0.8795128 +219.3552040;-48.1322682;30.1285104;4.7776950;0.1002043;6.5998794;-0.7171148 +219.5551631;-48.1172375;29.9291302;4.7974946;0.0978487;6.5781168;-0.5686368 +219.7551223;-48.0983059;29.7300536;4.8168301;0.0955356;6.5608088;-0.4326681 +219.9550815;-48.0755785;29.5314086;4.8357052;0.0932739;6.5476088;-0.3083983 +220.1550406;-48.0491479;29.3332025;4.8541332;0.0910462;6.5381837;-0.1939717 +220.3549998;-48.0191130;29.1355097;4.8721199;0.0888628;6.5322487;-0.0889016 +220.5549590;-47.9855723;28.9383943;4.8896732;0.0867180;6.5295268;0.0079200 +220.7549181;-47.9486144;28.7418672;4.9068026;0.0846036;6.5297693;0.0976038 +220.9548773;-47.9083424;28.5460198;4.9235116;0.0825353;6.5327575;0.1801308 +221.1548365;-47.8648405;28.3508488;4.9398109;0.0804924;6.5382688;0.2570202 +221.3547956;-47.8182026;28.1564022;4.9557048;0.0784851;6.5461245;0.3283554 +221.5547548;-47.7685213;27.9627209;4.9712005;0.0765111;6.5561468;0.3947128 +221.7547140;-47.7158785;27.7698067;4.9863048;0.0745590;6.5681743;0.4570224 +221.9546731;-47.6603701;27.5777154;5.0010206;0.0726368;6.5820730;0.5153065 +222.1546323;-47.6020751;27.3864419;5.0153544;0.0707325;6.5977092;0.5704355 +222.3545914;-47.5410801;27.1960109;5.0293094;0.0688443;6.6149750;0.6227768 +222.5545506;-47.4774713;27.0064428;5.0428872;0.0669658;6.6337737;0.6728792 +222.7545098;-47.4113275;26.8177367;5.0560914;0.0651027;6.6540251;0.7207226 +222.9544689;-47.3427347;26.6299131;5.0689232;0.0632428;6.6756483;0.7670670 +223.1544281;-47.2717715;26.4429701;5.0813841;0.0613930;6.6985853;0.8117901 +223.3543873;-47.1985183;26.2569111;5.0934763;0.0595519;6.7227743;0.8551285 +223.5543464;-47.1230551;26.0717385;5.1052004;0.0577135;6.7481609;0.8975262 +223.7543056;-47.0454608;25.8874510;5.1165576;0.0558850;6.7747039;0.9387850 +223.9542648;-46.9658099;25.7040372;5.1275497;0.0540560;6.8023562;0.9795397 +224.1542239;-46.8841829;25.5214991;5.1381763;0.0522326;6.8310897;1.0196185 +224.3541831;-46.8006536;25.3398229;5.1484389;0.0504138;6.8608710;1.0591932 +224.5541423;-46.7152955;25.1589945;5.1583378;0.0485946;6.8916719;1.0986057 +224.7541014;-46.6281889;24.9790134;5.1678730;0.0467812;6.9234741;1.1376642 +224.9540606;-46.5393961;24.7998418;5.1770461;0.0449636;6.9562538;1.1769487 +225.1540198;-46.4490002;24.6214844;5.1858553;0.0431481;6.9900036;1.2162410 +225.3539789;-46.3570689;24.4439135;5.1943019;0.0413363;7.0247097;1.2555567 +225.5539381;-46.2636695;24.2671019;5.2023867;0.0395258;7.0603589;1.2950950 +225.7538973;-46.1688830;24.0910478;5.2101091;0.0377178;7.0969430;1.3348787 +225.9538564;-46.0727620;23.9156961;5.2174685;0.0358846;7.1344546;1.3764017 +226.1538156;-45.9753911;23.7410491;5.2244603;0.0340486;7.1729276;1.4185782 +226.3537747;-45.8768349;23.5670719;5.2310869;0.0322640;7.2123648;1.4586661 +226.5537339;-45.7771541;23.3937271;5.2373680;0.0305585;7.2526928;1.4952969 +226.7536931;-45.6764207;23.2210027;5.2433075;0.0288502;7.2938021;1.5329046 +226.9536522;-45.5746808;23.0488637;5.2490904;0.0292418;7.3357062;1.4583774 +227.1536114;-45.4719355;22.8773216;5.2550051;0.0299177;7.3753521;1.3706437 +227.3535706;-45.3681652;22.7063970;5.2610752;0.0311260;7.4124195;1.2560806 +227.5535297;-45.2633314;22.5361232;5.2675070;0.0332056;7.4462268;1.0960967 +227.7534889;-45.1573681;22.3665472;5.2743549;0.0352879;7.4756031;0.9398902 +227.9534481;-45.0502113;22.1977235;5.2816178;0.0373528;7.5007014;0.7888276 +228.1534072;-44.9417972;22.0297060;5.2892932;0.0394183;7.5217012;0.6420634 +228.3533664;-44.8320620;21.8625481;5.2973822;0.0414903;7.5387506;0.4994530 +228.5533256;-44.7209432;21.6963054;5.3058867;0.0435728;7.5519866;0.3609537 +228.7532847;-44.6083824;21.5310404;5.3148079;0.0456589;7.5615378;0.2271225 +228.9532439;-44.4943143;21.3668053;5.3241458;0.0477369;7.5675415;0.0987747 +229.1532031;-44.3786859;21.2036697;5.3338993;0.0498194;7.5701510;-0.0247117 +229.3531622;-44.2614380;21.0416939;5.3440696;0.0519024;7.5694982;-0.1430038 +229.5531214;-44.1425135;20.8809411;5.3546563;0.0539862;7.5657196;-0.2560392 +229.7530806;-44.0218654;20.7214877;5.3656601;0.0560773;7.5589496;-0.3641342 +229.9530397;-43.8994304;20.5633886;5.3770823;0.0581660;7.5493109;-0.4666709 +230.1529989;-43.7751693;20.4067300;5.3889227;0.0602640;7.5369400;-0.5642945 +230.3529580;-43.6490294;20.2515800;5.4011832;0.0623648;7.5219540;-0.6566132 +230.5529172;-43.5209608;20.0980105;5.4138641;0.0644692;7.5044787;-0.7436704 +230.7528764;-43.3909318;19.9461148;5.4269662;0.0665859;7.4846372;-0.8259687 +230.9528355;-43.2588804;19.7959506;5.4404927;0.0687017;7.4625380;-0.9027667 +231.1527947;-43.1247863;19.6476232;5.4544429;0.0708326;7.4383090;-0.9750285 +231.3527539;-42.9886048;19.5012098;5.4688204;0.0729710;7.4120516;-1.0423359 +231.5527130;-42.8502952;19.3567925;5.4836265;0.0751182;7.3838784;-1.2199705 +231.7526722;-42.7098458;19.2144830;5.4988624;0.0772845;7.3507667;-1.3866066 +231.9526314;-42.5671960;19.0743429;5.5145337;0.0794524;7.3129503;-1.3177802 +232.1525905;-42.4223495;18.9364981;5.5306394;0.0816435;7.2768288;-1.2671591 +232.3525497;-42.2752720;18.8010363;5.5471851;0.0838472;7.2419250;-1.2550322 +232.5525089;-42.1259348;18.6680511;5.5641732;0.0860656;7.2071885;-1.2430213 +232.7524680;-41.9743515;18.5376730;5.5816056;0.0883122;7.1726187;-1.2311255 +232.9524272;-41.8204632;18.4099700;5.5994905;0.0905612;7.1382148;-1.2193434 +233.1523864;-41.6643046;18.2850881;5.6178263;0.0928434;7.1039758;-1.2076741 +233.3523455;-41.5058546;18.1631267;5.6366213;0.0951494;7.0699011;-1.1961165 +233.5523047;-41.3451005;18.0441929;5.6558812;0.0974852;7.0359898;-1.1846695 +233.7522638;-41.1820854;17.9284341;5.6756091;0.0998601;7.0022412;-1.1733321 +233.9522230;-41.0167571;17.8159300;5.6958199;0.1022775;6.9686544;-1.1621031 +234.1521822;-40.8491844;17.7068449;5.7165166;0.1047447;6.9352288;-1.1509816 +234.3521413;-40.6793633;17.6012929;5.7377112;0.1072601;6.9019634;-1.1399666 +234.5521005;-40.5073034;17.4993991;5.7594172;0.1098405;6.8688577;-1.1290570 +234.7520597;-40.3330780;17.4013260;5.7816408;0.1124739;6.8359107;-1.1182517 +234.9520188;-40.1566520;17.3071753;5.8044039;0.1151939;6.8031218;-1.1075499 +235.1519780;-39.9781287;17.2171257;5.8277152;0.1179840;6.7704901;-1.0969505 +235.3519372;-39.7975297;17.1313121;5.8515912;0.1208530;6.7380150;-1.0864525 +235.5518963;-39.6148958;17.0498816;5.8760546;0.1238309;6.7056956;-1.0760550 +235.7518555;-39.4303326;16.9730107;5.9011168;0.1268810;6.6735312;-1.0657570 +235.9518147;-39.2438392;16.9008321;5.9268088;0.1300881;6.6415212;-1.0555576 +236.1517738;-39.0555563;16.8335378;5.9531496;0.1333968;6.6096646;-1.0454558 +236.3517330;-38.8655435;16.7712886;5.9801622;0.1368252;6.5779609;-1.0354506 +236.5516922;-38.6738871;16.7142578;6.0078800;0.1404158;6.5464092;-1.0255412 +236.7516513;-38.4807332;16.6626377;6.0363223;0.1441082;6.5150089;-1.0157267 +236.9516105;-38.2861312;16.6165956;6.0655315;0.1480455;6.4837592;-1.0060060 +237.1515697;-38.0902798;16.5763402;6.0955413;0.1521469;6.4526594;-0.9963784 +237.3515288;-37.8932872;16.5420597;6.1263764;0.1561789;6.4217088;-0.9868429 +237.5514880;-37.6953095;16.5139459;6.1580025;0.1601567;6.3909066;-0.9773987 +237.7514471;-37.4965768;16.4921906;6.1904343;0.1643022;6.3602521;-0.9680449 +237.9514063;-37.2971964;16.4769476;6.2233423;0.1647537;6.3297447;-0.9587805 +238.1513655;-37.0974409;16.4682815;6.2563312;0.1652345;6.2993836;-0.9496049 +238.3513246;-36.8975170;16.4662154;0.0061321;0.1635991;6.2691682;-0.9405170 +238.5512838;-36.6976230;16.4706856;0.0384582;0.1597619;6.2390977;-0.9315161 +238.7512430;-36.4979503;16.4815402;0.0700361;0.1560801;6.2091714;-0.9226014 +238.9512021;-36.2987509;16.4986079;0.1007429;0.1511028;6.1793887;-0.9137720 +239.1511613;-36.1001273;16.5216893;0.1304713;0.1462543;6.1497488;-0.9050271 +239.3511205;-35.9022729;16.5505680;0.1592435;0.1415406;6.1202511;-0.8963658 +239.5510796;-35.7053210;16.5850332;0.1870797;0.1369043;6.0908949;-0.8963658 +239.7510388;-35.5093556;16.6248832;0.2140034;0.1323790;6.0613965;-0.7820779 +239.9509980;-35.3145604;16.6698957;0.2400295;0.1279789;6.0355414;-0.5599027 +240.1509571;-35.1209457;16.7198868;0.2651878;0.1236575;6.0169631;-0.3600946 +240.3509163;-34.9286386;16.7746466;0.2894903;0.1194358;6.0049843;-0.1805853 +240.5508755;-34.7376988;16.8339816;0.3129549;0.1152782;5.9989680;-0.0175838 +240.7508346;-34.5481459;16.8977128;0.3355987;0.1111916;5.9983818;0.1307287 +240.9507938;-34.3601051;16.9656252;0.3574283;0.1071848;6.0027382;0.2658486 +241.1507530;-34.1735267;17.0375659;0.3784654;0.1032260;6.0115874;0.3905293 +241.3507121;-33.9884868;17.1133368;0.3987158;0.0993348;6.0245633;0.5053755 +241.5506713;-33.8049918;17.1927664;0.4181928;0.0954880;6.0413137;0.6124409 +241.7506304;-33.6230171;17.2756988;0.4369077;0.0916856;6.0615508;0.7127264 +241.9505896;-33.4426390;17.3619317;0.4548632;0.0879328;6.0850169;0.8069307 +242.1505488;-33.2637708;17.4513397;0.4720743;0.0842089;6.1114758;0.8966147 +242.3505079;-33.0864470;17.5437399;0.4885436;0.0805271;6.1407418;0.9819577 +242.5504671;-32.9106363;17.6389819;0.5042794;0.0768724;6.1726342;1.0641509 +242.7504263;-32.7362854;17.7369294;0.5192892;0.0732444;6.2070110;1.1437396 +242.9503854;-32.5634256;17.8373978;0.5335735;0.0696453;6.2437479;1.2211283 +243.1503446;-32.3919537;17.9402805;0.5471420;0.0660631;6.2827335;1.2972226 +243.3503038;-32.2218667;18.0454126;0.5599951;0.0624957;6.3238851;1.3725040 +243.5502629;-32.0531085;18.1526609;0.5721354;0.0589367;6.3671353;1.4475969 +243.7502221;-31.8856079;18.2619024;0.5835667;0.0553913;6.4124358;1.5226239 +243.9501813;-31.7193540;18.3729746;0.5942873;0.0518457;6.4597413;1.5984831 +244.1501404;-31.5542417;18.4857773;0.6043009;0.0483090;6.5090338;1.6750888 +244.3500996;-31.3902334;18.6001651;0.6136077;0.0447775;6.5602911;1.7528981 +244.5500588;-31.2272574;18.7160156;0.6222084;0.0412484;6.6135040;1.8323233 +244.7500179;-31.0652320;18.8332140;0.6301045;0.0377257;6.6686742;1.9134661 +244.9499771;-30.9041094;18.9516210;0.6372956;0.0342025;6.7258045;1.9969209 +245.1499363;-30.7437915;19.0711338;0.6437829;0.0306831;6.7849135;2.0827727 +245.3498954;-30.5842119;19.1916264;0.6495666;0.0271652;6.8460200;2.1714112 +245.5498546;-30.4252904;19.3129831;0.6546468;0.0236478;6.9091517;2.2631852 +245.7498137;-30.2669419;19.4350920;0.6590240;0.0201323;6.9743434;2.3583164 +245.9497729;-30.1090877;19.5578361;0.6626980;0.0166157;7.0416333;2.4572640 +246.1497321;-29.9516433;19.6811033;0.6656690;0.0130999;7.1110692;2.5602608 +246.3496912;-29.7945198;19.8047844;0.6679369;0.0095835;7.1827015;2.6677070 +246.5496504;-29.6376346;19.9287655;0.6695016;0.0060663;7.2565877;2.7799724 +246.7496096;-29.4809043;20.0529335;0.6703629;0.0025485;7.3327912;2.8974142 +246.9495687;-29.3242279;20.1771887;0.6705206;-0.0009712;7.4113802;2.9138115 +247.1495279;-29.1675367;20.3014060;0.6699745;-0.0044919;7.4895823;2.6479305 +247.3494871;-29.0107279;20.4254875;0.6687241;-0.0080150;7.5599470;2.3810545 +247.5494462;-28.8537213;20.5493167;0.6667689;-0.0115403;7.6226653;2.1142186 +247.7494054;-28.6964391;20.6727757;0.6641089;-0.0150676;7.6779256;1.8484657 +247.9493646;-28.5387679;20.7957740;0.6607428;-0.0185989;7.7259159;1.5846849 +248.1493237;-28.3806561;20.9181729;0.6566706;-0.0221328;7.7668218;1.3239579 +248.3492829;-28.2219954;21.0398776;0.6518911;-0.0256721;7.8008330;1.0670637 +248.5492421;-28.0627128;21.1607656;0.6464034;-0.0292166;7.8281373;0.8149404 +248.7492012;-27.9027394;21.2807114;0.6402070;-0.0327637;7.8489263;0.5686265 +248.9491604;-27.7419615;21.3996230;0.6333001;-0.0363159;7.8633993;0.3287984 +249.1491196;-27.5803433;21.5173500;0.6256831;-0.0398730;7.8717559;0.0962543 +249.3490787;-27.4177809;21.6337925;0.6173528;-0.0434542;7.8742005;-0.1294751 +249.5490379;-27.2542140;21.7488171;0.6083036;-0.0470550;7.8709119;-0.3474067 +249.7489970;-27.0895876;21.8622870;0.5985352;-0.0506259;7.8620812;-0.5538235 +249.9489562;-26.9238009;21.9740997;0.5880802;-0.0539415;7.8479829;-0.7344150 +250.1489154;-26.7568323;22.0841082;0.5769629;-0.0572570;7.8292484;-0.9053389 +250.3488745;-26.5886171;22.1922034;0.5653168;-0.0584321;7.8060918;-0.9358886 +250.5488337;-26.4191471;22.2983294;0.5536429;-0.0583310;7.7820813;-0.8868489 +250.7487929;-26.2484495;22.4024724;0.5419903;-0.0581317;7.7592604;-0.8341796 +250.9487520;-26.0765579;22.5046251;0.5304528;-0.0572695;7.7377334;-0.7443418 +251.1487112;-25.9035028;22.6048056;0.5190866;-0.0564165;7.7184741;-0.6596538 +251.3486704;-25.7293313;22.7030258;0.5078859;-0.0556393;7.7013658;-0.5837502 +251.5486295;-25.5540777;22.7993021;0.4968338;-0.0549058;7.6861943;-0.5141977 +251.7485887;-25.3777748;22.8936501;0.4859276;-0.0541792;7.6728056;-0.4484693 +251.9485479;-25.2004658;22.9860797;0.4751657;-0.0534646;7.6611092;-0.3866312 +252.1485070;-25.0221729;23.0766114;0.4645458;-0.0527558;7.6510113;-0.3280883 +252.3484662;-24.8429389;23.1652552;0.4540666;-0.0520629;7.6424319;-0.2732325 +252.5484254;-24.6627909;23.2520289;0.4437245;-0.0513802;7.6352796;-0.2215294 +252.7483845;-24.4817566;23.3369491;0.4335181;-0.0507039;7.6294758;-0.1725703 +252.9483437;-24.2998786;23.4200259;0.4234463;-0.0500377;7.6249516;-0.1264052 +253.1483029;-24.1171709;23.5012821;0.4135069;-0.0493763;7.6216360;-0.0825748 +253.3482620;-23.9336748;23.5807283;0.4036995;-0.0487194;7.6194693;-0.0409295 +253.5482212;-23.7494122;23.6583837;0.3940230;-0.0480667;7.6183951;-0.0013163 +253.7481803;-23.5644071;23.7342664;0.3844763;-0.0474187;7.6183605;0.0363501 +253.9481395;-23.3786996;23.8083880;0.3750592;-0.0467742;7.6193145;0.0722467 +254.1480987;-23.1922987;23.8807727;0.3657702;-0.0461337;7.6212103;0.1064538 +254.3480578;-23.0052436;23.9514327;0.3566092;-0.0454965;7.6240029;0.1391000 +254.5480170;-22.8175518;24.0203887;0.3475752;-0.0448627;7.6276502;0.1702785 +254.7479762;-22.6292441;24.0876599;0.3386674;-0.0442327;7.6321128;0.2000447 +254.9479353;-22.4403579;24.1532598;0.3298857;-0.0436050;7.6373521;0.2285672 +255.1478945;-22.2508983;24.2172131;0.3212288;-0.0429806;7.6433341;0.2558549 +255.3478537;-22.0609020;24.2795339;0.3126967;-0.0423590;7.6500246;0.2820198 +255.5478128;-21.8703829;24.3402437;0.3042886;-0.0417400;7.6573926;0.3071304 +255.7477720;-21.6793591;24.3993628;0.2960037;-0.0411240;7.6654086;0.3312211 +255.9477312;-21.4878644;24.4569064;0.2878423;-0.0405098;7.6740439;0.3544278 +256.1476903;-21.2959015;24.5128994;0.2798030;-0.0398984;7.6832735;0.3767380 +256.3476495;-21.1035038;24.5673575;0.2718860;-0.0392890;7.6930720;0.3982521 +256.5476087;-20.9106825;24.6203029;0.2640905;-0.0386817;7.7034164;0.4190148 +256.7475678;-20.7174531;24.6717564;0.2564161;-0.0380768;7.7142852;0.4390451 +256.9475270;-20.5238457;24.7217351;0.2488629;-0.0374732;7.7256572;0.4584563 +257.1474862;-20.3298614;24.7702637;0.2414298;-0.0368720;7.7375141;0.4772244 +257.3474453;-20.1355301;24.8173594;0.2341169;-0.0362722;7.7498371;0.4954354 +257.5474045;-19.9408607;24.8630448;0.2269238;-0.0356741;7.7626096;0.5131183 +257.7473636;-19.7458664;24.9073412;0.2198499;-0.0350779;7.7758160;0.5302835 +257.9473228;-19.5505736;24.9502672;0.2128955;-0.0344827;7.7894405;0.5470260 +258.1472820;-19.3549824;24.9918472;0.2060596;-0.0338893;7.8034704;0.5633162 +258.3472411;-19.1591189;25.0320998;0.1993424;-0.0332970;7.8178917;0.5792280 +258.5472003;-18.9629902;25.0710477;0.1927435;-0.0327059;7.8326926;0.5947793 +258.7471595;-18.7666077;25.1087127;0.1862625;-0.0321164;7.8478619;0.6099755 +258.9471186;-18.5699935;25.1451147;0.1798996;-0.0315275;7.8633884;0.6248969 +259.1470778;-18.3731479;25.1802775;0.1736540;-0.0309401;7.8792630;0.6395116 +259.3470370;-18.1760926;25.2142211;0.1675260;-0.0303534;7.8954758;0.6538834 +259.5469961;-17.9788337;25.2469683;0.1615151;-0.0297677;7.9120186;0.6680227 +259.7469553;-17.7813806;25.2785412;0.1556211;-0.0291832;7.9288834;0.6819319 +259.9469145;-17.5837517;25.3089605;0.1498442;-0.0285990;7.9460625;0.6956794 +260.1468736;-17.3859473;25.3382499;0.1441838;-0.0280159;7.9635497;0.7092328 +260.3468328;-17.1879852;25.3664303;0.1386400;-0.0274334;7.9813382;0.7226481 +260.5467920;-16.9898706;25.3935244;0.1332127;-0.0268515;7.9994225;0.0231058 +260.7467511;-16.7916112;25.4195547;0.1279015;-0.0262705;8.0000000;0.0000000 +260.9467103;-16.5932217;25.4445427;0.1227066;-0.0256896;8.0000000;0.0000000 +261.1466695;-16.3947028;25.4685117;0.1176277;-0.0251096;8.0000000;0.0000000 +261.3466286;-16.1960685;25.4914834;0.1126648;-0.0245299;8.0000000;0.0000000 +261.5465878;-15.9973232;25.5134806;0.1078177;-0.0239506;8.0000000;0.0000000 +261.7465469;-15.7984734;25.5345258;0.1030864;-0.0233720;8.0000000;0.0000000 +261.9465061;-15.5995301;25.5546413;0.0984709;-0.0227933;8.0000000;0.0000000 +262.1464653;-15.4004947;25.5738501;0.0939709;-0.0222152;8.0000000;0.0000000 +262.3464244;-15.2013775;25.5921743;0.0895866;-0.0216373;8.0000000;0.0000000 +262.5463836;-15.0021825;25.6096370;0.0853177;-0.0210596;8.0000000;0.0000000 +262.7463428;-14.8029148;25.6262607;0.0811644;-0.0204823;8.0000000;0.0000000 +262.9463019;-14.6035822;25.6420681;0.0771265;-0.0199049;8.0000000;0.0000000 +263.1462611;-14.4041870;25.6570821;0.0732040;-0.0193279;8.0000000;0.0000000 +263.3462203;-14.2047360;25.6713252;0.0693969;-0.0187509;8.0000000;0.0000000 +263.5461794;-14.0052328;25.6848205;0.0657052;-0.0181740;8.0000000;0.0000000 +263.7461386;-13.8056816;25.6975907;0.0621288;-0.0175973;8.0000000;0.0000000 +263.9460978;-13.6060870;25.7096586;0.0586677;-0.0170203;8.0000000;0.0000000 +264.1460569;-13.4064525;25.7210472;0.0553220;-0.0164436;8.0000000;0.0000000 +264.3460161;-13.2067813;25.7317793;0.0520916;-0.0158668;8.0000000;0.0000000 +264.5459753;-13.0070774;25.7418778;0.0489766;-0.0152901;8.0000000;0.0000000 +264.7459344;-12.8073436;25.7513657;0.0459768;-0.0147135;8.0000000;0.0000000 +264.9458936;-12.6075822;25.7602660;0.0430924;-0.0141366;8.0000000;0.0000000 +265.1458527;-12.4077973;25.7686015;0.0403233;-0.0135598;8.0000000;0.0000000 +265.3458119;-12.2079896;25.7763954;0.0376696;-0.0129827;8.0000000;0.0000000 +265.5457711;-12.0081627;25.7836704;0.0351313;-0.0124056;8.0000000;0.0000000 +265.7457302;-11.8083191;25.7904498;0.0327084;-0.0118286;8.0000000;0.0000000 +265.9456894;-11.6084585;25.7967565;0.0304008;-0.0112514;8.0000000;0.0000000 +266.1456486;-11.4085860;25.8026134;0.0282087;-0.0106744;8.0000000;0.0000000 +266.3456077;-11.2086998;25.8080438;0.0261320;-0.0100968;8.0000000;0.0000000 +266.5455669;-11.0088037;25.8130706;0.0241708;-0.0095191;8.0000000;0.0000000 +266.7455261;-10.8088995;25.8177169;0.0223251;-0.0089413;8.0000000;0.0000000 +266.9454852;-10.6089849;25.8220058;0.0205950;-0.0083633;8.0000000;0.0000000 +267.1454444;-10.4090661;25.8259604;0.0189805;-0.0077853;8.0000000;0.0000000 +267.3454036;-10.2091391;25.8296037;0.0174815;-0.0072070;8.0000000;0.0000000 +267.5453627;-10.0092080;25.8329589;0.0160983;-0.0066285;8.0000000;0.0000000 +267.7453219;-9.8092739;25.8360491;0.0148307;-0.0060498;8.0000000;0.0000000 +267.9452811;-9.6093333;25.8388975;0.0136789;-0.0054709;8.0000000;0.0000000 +268.1452402;-9.4093930;25.8415271;0.0126428;-0.0048919;8.0000000;0.0000000 +268.3451994;-9.2094474;25.8439612;0.0117225;-0.0043124;8.0000000;0.0000000 +268.5451586;-9.0095009;25.8462228;0.0109182;-0.0037326;8.0000000;0.0000000 +268.7451177;-8.8095543;25.8483352;0.0102298;-0.0031523;8.0000000;0.0000000 +268.9450769;-8.6096031;25.8503216;0.0096577;-0.0025699;8.0000000;0.0000000 +269.1450360;-8.4096546;25.8522052;0.0092021;-0.0019874;8.0000000;0.0000000 +269.3449952;-8.2097021;25.8540094;0.0088636;-0.0013960;8.0000000;0.0000000 +269.5449544;-8.0097505;25.8557578;0.0086439;-0.0008013;8.0000000;0.0000000 +269.7449135;-7.8098001;25.8574742;0.0085433;-0.0002002;8.0000000;0.0000000 +269.9448727;-7.6098458;25.8591826;0.0085654;0.0004219;8.0000000;0.0000000 +270.1448319;-7.4098963;25.8609079;0.0087120;0.0010442;8.0000000;0.0000000 +270.3447910;-7.2099434;25.8626747;0.0089777;0.0015933;8.0000000;0.0000000 +270.5447502;-7.0099927;25.8645052;0.0093485;0.0021157;8.0000000;0.0000000 +270.7447094;-6.8100449;25.8664202;0.0098223;0.0025733;8.0000000;0.0000000 +270.9446685;-6.6100948;25.8684373;0.0103614;0.0028188;8.0000000;0.0000000 +271.1446277;-6.4101482;25.8705671;0.0109495;0.0030642;8.0000000;0.0000000 +271.3445869;-6.2102021;25.8728189;0.0115754;0.0031557;8.0000000;0.0000000 +271.5445460;-6.0102572;25.8751968;0.0122101;0.0031920;8.0000000;0.0000000 +271.7445052;-5.8103140;25.8777023;0.0128514;0.0032046;8.0000000;0.0000000 +271.9444644;-5.6103725;25.8803356;0.0134859;0.0031418;8.0000000;0.0000000 +272.1444235;-5.4104321;25.8830945;0.0141079;0.0030790;8.0000000;0.0000000 +272.3443827;-5.2104939;25.8859766;0.0147174;0.0030177;8.0000000;0.0000000 +272.5443419;-5.0105573;25.8889793;0.0153147;0.0029570;8.0000000;0.0000000 +272.7443010;-4.8106223;25.8921002;0.0159000;0.0028967;8.0000000;0.0000000 +272.9442602;-4.6106897;25.8953369;0.0164733;0.0028378;8.0000000;0.0000000 +273.1442193;-4.4107582;25.8986871;0.0170348;0.0027789;8.0000000;0.0000000 +273.3441785;-4.2108293;25.9021483;0.0175843;0.0027158;8.0000000;0.0000000 +273.5441377;-4.0109020;25.9057182;0.0181209;0.0026513;8.0000000;0.0000000 +273.7440968;-3.8109763;25.9093940;0.0186445;0.0025836;8.0000000;0.0000000 +273.9440560;-3.6110532;25.9131730;0.0191534;0.0025061;8.0000000;0.0000000 +274.1440152;-3.4111313;25.9170523;0.0196468;0.0024286;8.0000000;0.0000000 +274.3439743;-3.2112120;25.9210286;0.0201246;0.0023504;8.0000000;0.0000000 +274.5439335;-3.0112942;25.9250989;0.0205868;0.0022720;8.0000000;0.0000000 +274.7438927;-2.8113781;25.9292600;0.0210332;0.0021938;8.0000000;0.0000000 +274.9438518;-2.6114644;25.9335088;0.0214641;0.0021161;8.0000000;0.0000000 +275.1438110;-2.4115519;25.9378423;0.0218795;0.0020384;8.0000000;0.0000000 +275.3437702;-2.2116417;25.9422571;0.0222794;0.0019618;8.0000000;0.0000000 +275.5437293;-2.0117330;25.9467505;0.0226641;0.0018854;8.0000000;0.0000000 +275.7436885;-1.8118258;25.9513191;0.0230334;0.0018087;8.0000000;0.0000000 +275.9436477;-1.6119209;25.9559601;0.0233873;0.0017306;8.0000000;0.0000000 +276.1436068;-1.4120169;25.9606703;0.0237255;0.0016526;8.0000000;0.0000000 +276.3435660;-1.2121150;25.9654464;0.0240478;0.0015690;8.0000000;0.0000000 +276.5435252;-1.0122144;25.9702853;0.0243530;0.0014836;8.0000000;0.0000000 +276.7434843;-0.8123150;25.9751835;0.0246411;0.0013981;8.0000000;0.0000000 +276.9434435;-0.6124175;25.9801376;0.0249121;0.0013122;8.0000000;0.0000000 +277.1434026;-0.4125207;25.9851442;0.0251659;0.0012264;8.0000000;0.0000000 +277.3433618;-0.2126257;25.9901997;0.0254026;0.0011411;8.0000000;0.0000000 +277.5433210;-0.0127316;25.9953009;0.0256222;0.0010561;8.0000000;0.0000000 +277.7432801;0.1871616;26.0004443;0.0258249;0.0009714;8.0000000;0.0000000 +277.9432393;0.3870533;26.0056265;0.0260108;0.0008876;8.0000000;0.0000000 +278.1431985;0.5869447;26.0108442;0.0261799;0.0008037;8.0000000;0.0000000 +278.3431576;0.7868347;26.0160940;0.0263323;0.0007208;8.0000000;0.0000000 +278.5431168;0.9867242;26.0213726;0.0264681;0.0006381;8.0000000;0.0000000 +278.7430760;1.1866132;26.0266768;0.0265875;0.0005555;8.0000000;0.0000000 +278.9430351;1.3865012;26.0320031;0.0266903;0.0004735;8.0000000;0.0000000 +279.1429943;1.5863892;26.0373484;0.0267768;0.0003914;8.0000000;0.0000000 +279.3429535;1.7862762;26.0427093;0.0268470;0.0003105;8.0000000;0.0000000 +279.5429126;1.9861632;26.0480826;0.0269010;0.0002298;8.0000000;0.0000000 +279.7428718;2.1860501;26.0534651;0.0269389;0.0001498;8.0000000;0.0000000 +279.9428310;2.3859364;26.0588536;0.0269610;0.0000712;8.0000000;0.0000000 +280.1427901;2.5858231;26.0642450;0.0269674;-0.0000074;8.0000000;0.0000000 +280.3427493;2.7857094;26.0696360;0.0269581;-0.0000850;8.0000000;0.0000000 +280.5427085;2.9855960;26.0750237;0.0269333;-0.0001624;8.0000000;0.0000000 +280.7426676;3.1854829;26.0804049;0.0268932;-0.0002395;8.0000000;0.0000000 +280.9426268;3.3853697;26.0857764;0.0268376;-0.0003162;8.0000000;0.0000000 +281.1425859;3.5852573;26.0911354;0.0267667;-0.0003929;8.0000000;0.0000000 +281.3425451;3.7851448;26.0964787;0.0266806;-0.0004680;8.0000000;0.0000000 +281.5425043;3.9850331;26.1018032;0.0265796;-0.0005427;8.0000000;0.0000000 +281.7424634;4.1849221;26.1071061;0.0264636;-0.0006167;8.0000000;0.0000000 +281.9424226;4.3848114;26.1123843;0.0263330;-0.0006891;8.0000000;0.0000000 +282.1423818;4.5847019;26.1176350;0.0261880;-0.0007615;8.0000000;0.0000000 +282.3423409;4.7845927;26.1228552;0.0260285;-0.0008342;8.0000000;0.0000000 +282.5423001;4.9844846;26.1280421;0.0258544;-0.0009070;8.0000000;0.0000000 +282.7422593;5.1843775;26.1331927;0.0256627;-0.0010850;8.0000000;0.0000000 +282.9422184;5.3842712;26.1382990;0.0254016;-0.0015265;8.0000000;0.0000000 +283.1421776;5.5841670;26.1433443;0.0250523;-0.0019679;8.0000000;0.0000000 +283.3421368;5.7840626;26.1483078;0.0245565;-0.0031479;8.0000000;0.0000000 +283.5420959;5.9839628;26.1531455;0.0237892;-0.0045271;8.0000000;0.0000000 +283.7420551;6.1838679;26.1578024;0.0227497;-0.0057788;8.0000000;0.0000000 +283.9420143;6.3837745;26.1622292;0.0215003;-0.0067183;8.0000000;0.0000000 +284.1419734;6.5836944;26.1663876;0.0200630;-0.0076575;8.0000000;0.0000000 +284.3419326;6.7836134;26.1702381;0.0184085;-0.0089680;8.0000000;0.0000000 +284.5418918;6.9835427;26.1737303;0.0164745;-0.0103766;8.0000000;0.0000000 +284.7418509;7.1834810;26.1768076;0.0142578;-0.0118166;8.0000000;0.0000000 +284.9418101;7.3834212;26.1794121;0.0117434;-0.0133329;8.0000000;0.0000000 +285.1417692;7.5833720;26.1814836;0.0089257;-0.0148492;8.0000000;0.0000000 +285.3417284;7.7833246;26.1829615;0.0058060;-0.0163517;8.0000000;0.0000000 +285.5416876;7.9832822;26.1837856;0.0023864;-0.0178508;8.0000000;0.0000000 +285.7416467;8.1832423;26.1838959;6.2818525;-0.0193466;8.0000000;0.0000000 +285.9416059;8.3831995;26.1832327;6.2778352;-0.0208345;8.0000000;0.0000000 +286.1415651;8.5831539;26.1817365;6.2735204;-0.0223228;8.0000000;0.0000000 +286.3415242;8.7830986;26.1793478;6.2689085;-0.0238038;8.0000000;0.0000000 +286.5414834;8.9830298;26.1760075;6.2640008;-0.0252836;8.0000000;0.0000000 +286.7414426;9.1829419;26.1716564;6.2587971;-0.0267634;8.0000000;0.0000000 +286.9414017;9.3828277;26.1662355;6.2532976;-0.0282427;8.0000000;0.0000000 +287.1413609;9.5826790;26.1596859;6.2475022;-0.0297233;8.0000000;0.0000000 +287.3413201;9.7824893;26.1519486;6.2414110;-0.0312013;8.0000000;0.0000000 +287.5412792;9.9822462;26.1429648;6.2350241;-0.0326804;8.0000000;0.0000000 +287.7412384;10.1819398;26.1326759;6.2283414;-0.0341596;8.0000000;0.0000000 +287.9411976;10.3815605;26.1210231;6.2213630;-0.0356382;8.0000000;0.0000000 +288.1411567;10.5810894;26.1079484;6.2140889;-0.0371192;8.0000000;0.0000000 +288.3411159;10.7805202;26.0933927;6.2065186;-0.0385983;8.0000000;0.0000000 +288.5410751;10.9798299;26.0772985;6.1986524;-0.0400798;8.0000000;0.0000000 +288.7410342;11.1790033;26.0596075;6.1904898;-0.0415623;8.0000000;0.0000000 +288.9409934;11.3780270;26.0402615;6.1820308;-0.0430452;8.0000000;0.0000000 +289.1409525;11.5768699;26.0192038;6.1732750;-0.0445320;8.0000000;0.0000000 +289.3409117;11.7755252;25.9963756;6.1642217;-0.0460178;8.0000000;0.0000000 +289.5408709;11.9739575;25.9717208;6.1548712;-0.0475077;8.0000000;0.0000000 +289.7408300;12.1721449;25.9451825;6.1452224;-0.0490003;8.0000000;0.0000000 +289.9407892;12.3700694;25.9167026;6.1352748;-0.0504951;8.0000000;0.0000000 +290.1407484;12.5676860;25.8862273;6.1250282;-0.0519959;8.0000000;0.0000000 +290.3407075;12.7649862;25.8536972;6.1144807;-0.0534979;8.0000000;0.0000000 +290.5406667;12.9619210;25.8190595;6.1036326;-0.0550067;8.0000000;0.0000000 +290.7406259;13.1584604;25.7822583;6.0924823;-0.0565205;8.0000000;0.0000000 +290.9405850;13.3545800;25.7432365;6.0810285;-0.0580390;8.0000000;0.0000000 +291.1405442;13.5502205;25.7019440;6.0692709;-0.0595663;8.0000000;0.0000000 +291.3405034;13.7453692;25.6583211;6.0572067;-0.0610972;8.0000000;0.0000000 +291.5404625;13.9399628;25.6123192;6.0448359;-0.0626383;8.0000000;0.0000000 +291.7404217;14.1339621;25.5638844;6.0321562;-0.0641874;8.0000000;0.0000000 +291.9403809;14.3273340;25.5129609;6.0191653;-0.0657458;8.0000000;0.0000000 +292.1403400;14.5200044;25.4595040;6.0058626;-0.0673166;8.0000000;0.0000000 +292.3402992;14.7119539;25.4034538;5.9922439;-0.0688944;8.0000000;0.0000000 +292.5402584;14.9031043;25.3447673;5.9783090;-0.0704863;8.0000000;0.0000000 +292.7402175;15.0934055;25.2833935;5.9640547;-0.0720908;8.0000000;0.0000000 +292.9401767;15.2828131;25.2192793;5.9494772;-0.0737117;8.0000000;0.0000000 +293.1401358;15.4712391;25.1523860;5.9345751;-0.0753490;8.0000000;0.0000000 +293.3400950;15.6586526;25.0826552;5.9193431;-0.0769987;8.0000000;0.0000000 +293.5400542;15.8449613;25.0100507;5.9037800;-0.0786679;8.0000000;0.0000000 +293.7400133;16.0301019;24.9345257;5.8878816;-0.0803563;8.0000000;0.0000000 +293.9399725;16.2140151;24.8560314;5.8716421;-0.0820699;8.0000000;0.0000000 +294.1399317;16.3966009;24.7745362;5.8550591;-0.0838047;8.0000000;0.0000000 +294.3398908;16.5778100;24.6899860;5.8381256;-0.0855643;8.0000000;0.0000000 +294.5398500;16.7575384;24.6023515;5.8208382;-0.0873509;8.0000000;0.0000000 +294.7398092;16.9357067;24.5115923;5.8031911;-0.0891694;8.0000000;0.0000000 +294.9397683;17.1122360;24.4176668;5.7851743;-0.0910358;8.0000000;0.0000000 +295.1397275;17.2870155;24.3205495;5.7667825;-0.0929311;8.0000000;0.0000000 +295.3396867;17.4599706;24.2201954;5.7480101;-0.0948284;8.0000000;0.0000000 +295.5396458;17.6309864;24.1165831;5.7288563;-0.0967555;8.0000000;0.0000000 +295.7396050;17.7999626;24.0096838;5.7093200;-0.0985581;8.0000000;0.0000000 +295.9395642;17.9668029;23.8994740;5.6894574;-0.1001147;8.0000000;0.0000000 +296.1395233;18.1314049;23.7859455;5.6692806;-0.1016977;8.0000000;0.0000000 +296.3394825;18.2936624;23.6691090;5.6489843;-0.1010102;8.0000000;0.0000000 +296.5394416;18.4535365;23.5490123;5.6288882;-0.0999966;8.0000000;0.0000000 +296.7394008;18.6109779;23.4257427;5.6089990;-0.0988016;8.0000000;0.0000000 +296.9393600;18.7659469;23.2993934;5.5893974;-0.0972677;8.0000000;0.0000000 +297.1393191;18.9184438;23.1700416;5.5700969;-0.0957720;8.0000000;0.0000000 +297.3392783;19.0684184;23.0378085;5.5510950;-0.0942990;8.0000000;0.0000000 +297.5392375;19.2158833;22.9027618;5.5323838;-0.0928545;8.0000000;0.0000000 +297.7391966;19.3608160;22.7649999;5.5139573;-0.0914598;8.0000000;0.0000000 +297.9391558;19.5031974;22.6246181;5.4958043;-0.0901196;8.0000000;0.0000000 +298.1391150;19.6430408;22.4816782;5.4779143;-0.0888098;8.0000000;0.0000000 +298.3390741;19.7803059;22.3362965;5.4602849;-0.0875365;8.0000000;0.0000000 +298.5390333;19.9150160;22.1885228;5.4429061;-0.0862887;8.0000000;0.0000000 +298.7389925;20.0471567;22.0384463;5.4257739;-0.0850716;8.0000000;0.0000000 +298.9389516;20.1767182;21.8861525;5.4088828;-0.0838843;8.0000000;0.0000000 +299.1389108;20.3037211;21.7316897;5.3922248;-0.0827225;8.0000000;0.0000000 +299.3388700;20.4281353;21.5751679;5.3757990;-0.0815816;8.0000000;0.0000000 +299.5388291;20.5499890;21.4166253;5.3595981;-0.0804623;8.0000000;0.0000000 +299.7387883;20.6692764;21.2561424;5.3436185;-0.0793679;8.0000000;0.0000000 +299.9387475;20.7859958;21.0937952;5.3278563;-0.0782945;8.0000000;0.0000000 +300.1387066;20.9001707;20.9296241;5.3123053;-0.0772411;8.0000000;0.0000000 +300.3386658;21.0117829;20.7637291;5.2969649;-0.0762050;8.0000000;0.0000000 +300.5386249;21.1208622;20.5961407;5.2818289;-0.0751873;8.0000000;0.0000000 +300.7385841;21.2274100;20.4269307;5.2668944;-0.0741870;8.0000000;0.0000000 +300.9385433;21.3314313;20.2561664;5.2521593;-0.0732001;8.0000000;0.0000000 +301.1385024;21.4329499;20.0838846;5.2376187;-0.0722319;8.0000000;0.0000000 +301.3384616;21.5319606;19.9101703;5.2232720;-0.0712711;8.0000000;0.0000000 +301.5384208;21.6284906;19.7350537;5.2091156;-0.0703232;8.0000000;0.0000000 +301.7383799;21.7225488;19.5585966;5.1951473;-0.0693865;8.0000000;0.0000000 +301.9383391;21.8141468;19.3808572;5.1813662;-0.0684577;8.0000000;0.0000000 +302.1382983;21.9033085;19.2018701;5.1677685;-0.0675441;8.0000000;0.0000000 +302.3382574;21.9900392;19.0217064;5.1543539;-0.0666334;8.0000000;0.0000000 +302.5382166;22.0743646;18.8403974;5.1411199;-0.0657348;8.0000000;0.0000000 +302.7381758;22.1562996;18.6579952;5.1280642;-0.0648491;8.0000000;0.0000000 +302.9381349;22.2358610;18.4745496;5.1151850;-0.0639724;8.0000000;0.0000000 +303.1380941;22.3130716;18.2900957;5.1024796;-0.0631070;8.0000000;0.0000000 +303.3380533;22.3879462;18.1046878;5.0899469;-0.0622482;8.0000000;0.0000000 +303.5380124;22.4605084;17.9183594;5.0775848;-0.0613999;8.0000000;0.0000000 +303.7379716;22.5307777;17.7311535;5.0653914;-0.0605551;8.0000000;0.0000000 +303.9379308;22.5987747;17.5431119;5.0533677;-0.0597080;8.0000000;0.0000000 +304.1378899;22.6645218;17.3542717;5.0415123;-0.0588711;8.0000000;0.0000000 +304.3378491;22.7280417;17.1646689;5.0298188;-0.0580933;8.0000000;0.0000000 +304.5378082;22.7893541;16.9743430;5.0182790;-0.0573296;8.0000000;0.0000000 +304.7377674;22.8484804;16.7833274;5.0068845;-0.0567373;8.0000000;0.0000000 +304.9377266;22.9054355;16.5916523;4.9955741;-0.0563912;8.0000000;0.0000000 +305.1376857;22.9602255;16.3993478;4.9843324;-0.0560491;8.0000000;0.0000000 +305.3376449;23.0128480;16.2064398;4.9730085;-0.0573801;8.0000000;0.0000000 +305.5376041;23.0632540;16.0129392;4.9613829;-0.0589002;8.0000000;0.0000000 +305.7375632;23.1113775;15.8188577;4.9494445;-0.0606334;8.0000000;0.0000000 +305.9375224;23.1571435;15.6242077;4.9371151;-0.0626880;8.0000000;0.0000000 +306.1374816;23.2004661;15.4289986;4.9243736;-0.0647539;8.0000000;0.0000000 +306.3374407;23.2412576;15.2332438;4.9112161;-0.0668513;8.0000000;0.0000000 +306.5373999;23.2794284;15.0369634;4.8976374;-0.0689662;8.0000000;0.0000000 +306.7373591;23.3148889;14.8401745;4.8836347;-0.0710861;8.0000000;0.0000000 +306.9373182;23.3475489;14.6428998;4.8692079;-0.0732127;8.0000000;0.0000000 +307.1372774;23.3773164;14.4451747;4.8543546;-0.0753563;8.0000000;0.0000000 +307.3372366;23.4041026;14.2470140;4.8390706;-0.0775139;8.0000000;0.0000000 +307.5371957;23.4278133;14.0484688;4.8233535;-0.0796933;8.0000000;0.0000000 +307.7371549;23.4483573;13.8495704;4.8071988;-0.0818891;8.0000000;0.0000000 +307.9371141;23.4656421;13.6503574;4.7906025;-0.0841083;8.0000000;0.0000000 +308.1370732;23.4795733;13.4508942;4.7735609;-0.0863533;8.0000000;0.0000000 +308.3370324;23.4900592;13.2512036;4.7560668;-0.0886210;8.0000000;0.0000000 +308.5369915;23.4970045;13.0513699;4.7381170;-0.0909207;8.0000000;0.0000000 +308.7369507;23.5003157;12.8514424;4.7197045;-0.0932469;8.0000000;0.0000000 +308.9369099;23.4998986;12.6514806;4.7008228;-0.0956096;8.0000000;0.0000000 +309.1368690;23.4956592;12.4515802;4.6814666;-0.0980080;8.0000000;0.0000000 +309.3368282;23.4875023;12.2517798;4.6616252;-0.1004438;8.0000000;0.0000000 +309.5367874;23.4753351;12.0521973;4.6412934;-0.1029251;8.0000000;0.0000000 +309.7367465;23.4590630;11.8529073;4.6204615;-0.1054462;8.0000000;0.0000000 +309.9367057;23.4385917;11.6539961;4.5991193;-0.1080215;8.0000000;0.0000000 +310.1366649;23.4138312;11.4555917;4.5772590;-0.1106459;8.0000000;0.0000000 +310.3366240;23.3846841;11.2577615;4.5548663;-0.1133270;8.0000000;0.0000000 +310.5365832;23.3510639;11.0606563;4.5319323;-0.1160722;8.0000000;0.0000000 +310.7365424;23.3128784;10.8643850;4.5084439;-0.1188769;8.0000000;0.0000000 +310.9365015;23.2700367;10.6690690;4.4843856;-0.1217613;8.0000000;0.0000000 +311.1364607;23.2224562;10.4748685;4.4597456;-0.1247108;8.0000000;0.0000000 +311.3364199;23.1700437;10.2818994;4.4345059;-0.1277469;8.0000000;0.0000000 +311.5363790;23.1127218;10.0903405;4.4086509;-0.1308717;8.0000000;0.0000000 +311.7363382;23.0504077;9.9003482;4.3821777;-0.1337365;8.0000000;0.0000000 +311.9362974;22.9830350;9.7120853;4.3551879;-0.1362306;8.0000000;0.0000000 +312.1362565;22.9105612;9.5257326;4.3276905;-0.1388187;8.0000000;0.0000000 +312.3362157;22.8329652;9.3414543;4.3000578;-0.1372378;8.0000000;0.0000000 +312.5361748;22.7503397;9.1593699;4.2728034;-0.1353783;8.0000000;0.0000000 +312.7361340;22.6628168;8.9795894;4.2459345;-0.1330462;8.0000000;0.0000000 +312.9360932;22.5705449;8.8022019;4.2196368;-0.1300009;8.0000000;0.0000000 +313.1360523;22.4736897;8.6272663;4.1939383;-0.1270473;8.0000000;0.0000000 +313.3360115;22.3724265;8.4548556;4.1688215;-0.1241889;8.0000000;0.0000000 +313.5359707;22.2669099;8.2850071;4.1442687;-0.1214000;8.0000000;0.0000000 +313.7359298;22.1573019;8.1177706;4.1202652;-0.1187035;8.0000000;0.0000000 +313.9358890;22.0437573;7.9531853;4.0967926;-0.1160838;8.0000000;0.0000000 +314.1358482;21.9264177;7.7912724;4.0738364;-0.1135291;8.0000000;0.0000000 +314.3358073;21.8054402;7.6320748;4.0513836;-0.1110612;8.0000000;0.0000000 +314.5357665;21.6809520;7.4755963;4.0294182;-0.1086445;8.0000000;0.0000000 +314.7357257;21.5530946;7.3218599;4.0079300;-0.1062963;8.0000000;0.0000000 +314.9356848;21.4220012;7.1708789;3.9869051;-0.1040065;8.0000000;0.0000000 +315.1356440;21.2877885;7.0226482;3.9663323;-0.1017636;8.0000000;0.0000000 +315.3356032;21.1505978;6.8771903;3.9462039;-0.0995754;8.0000000;0.0000000 +315.5355623;21.0105312;6.7344855;3.9265084;-0.0974245;8.0000000;0.0000000 +315.7355215;20.8677120;6.5945371;3.9072387;-0.0953197;8.0000000;0.0000000 +315.9354807;20.7222548;6.4573394;3.8883863;-0.0932518;8.0000000;0.0000000 +316.1354398;20.5742557;6.3228696;3.8699429;-0.0912183;8.0000000;0.0000000 +316.3353990;20.4238404;6.1911320;3.8519039;-0.0892196;8.0000000;0.0000000 +316.5353581;20.2710912;6.0620922;3.8342610;-0.0872480;8.0000000;0.0000000 +316.7353173;20.1161147;5.9357375;3.8170095;-0.0853051;8.0000000;0.0000000 +316.9352765;19.9590092;5.8120474;3.8001448;-0.0833827;8.0000000;0.0000000 +317.1352356;19.7998544;5.6909872;3.7836611;-0.0814857;8.0000000;0.0000000 +317.3351948;19.6387595;5.5725445;3.7675561;-0.0796051;8.0000000;0.0000000 +317.5351540;19.4757927;5.4566760;3.7518246;-0.0777437;8.0000000;0.0000000 +317.7351131;19.3110449;5.3433553;3.7364633;-0.0759023;8.0000000;0.0000000 +317.9350723;19.1445993;5.2325501;3.7214691;-0.0740742;8.0000000;0.0000000 +318.1350315;18.9765236;5.1242177;3.7068382;-0.0722644;8.0000000;0.0000000 +318.3349906;18.8069091;5.0183308;3.6925691;-0.0704604;8.0000000;0.0000000 +318.5349498;18.6358141;4.9148409;3.6786591;-0.0686695;8.0000000;0.0000000 +318.7349090;18.4633145;4.8137102;3.6651057;-0.0668922;8.0000000;0.0000000 +318.9348681;18.2894801;4.7148971;3.6519071;-0.0651237;8.0000000;0.0000000 +319.1348273;18.1143687;4.6183533;3.6390605;-0.0633680;8.0000000;0.0000000 +319.3347865;17.9380538;4.5240392;3.6265647;-0.0616190;8.0000000;0.0000000 +319.5347456;17.7605870;4.4319029;3.6144174;-0.0598791;8.0000000;0.0000000 +319.7347048;17.5820297;4.3418981;3.6026172;-0.0581476;8.0000000;0.0000000 +319.9346640;17.4024394;4.2539762;3.5911628;-0.0564208;8.0000000;0.0000000 +320.1346231;17.2218663;4.1680848;3.5800528;-0.0547025;8.0000000;0.0000000 +320.3345823;17.0403667;4.0841747;3.5692860;-0.0529886;8.0000000;0.0000000 +320.5345414;16.8579872;4.0021919;3.5588613;-0.0512804;8.0000000;0.0000000 +320.7345006;16.6747764;3.9220834;3.5487775;-0.0495782;8.0000000;0.0000000 +320.9344598;16.4907808;3.8437953;3.5390338;-0.0478794;8.0000000;0.0000000 +321.1344189;16.3060443;3.7672724;3.5296294;-0.0461857;8.0000000;0.0000000 +321.3343781;16.1206078;3.6924584;3.5205634;-0.0444916;8.0000000;0.0000000 +321.5343373;15.9345142;3.6192975;3.5118361;-0.0428005;8.0000000;0.0000000 +321.7342964;15.7478008;3.5477317;3.5034465;-0.0411129;8.0000000;0.0000000 +321.9342556;15.5605048;3.4777031;3.4953941;-0.0394267;8.0000000;0.0000000 +322.1342148;15.3726650;3.4091542;3.4876788;-0.0377435;8.0000000;0.0000000 +322.3341739;15.1843091;3.3420233;3.4802999;-0.0360604;8.0000000;0.0000000 +322.5341331;14.9954770;3.2762534;3.4732574;-0.0343788;8.0000000;0.0000000 +322.7340923;14.8061965;3.2117829;3.4665511;-0.0326984;8.0000000;0.0000000 +322.9340514;14.6164972;3.1485510;3.4601807;-0.0310180;8.0000000;0.0000000 +323.1340106;14.4264138;3.0864982;3.4541464;-0.0293389;8.0000000;0.0000000 +323.3339698;14.2359629;3.0255595;3.4484476;-0.0276594;8.0000000;0.0000000 +323.5339289;14.0451824;2.9656765;3.4430848;-0.0259804;8.0000000;0.0000000 +323.7338881;13.8540925;2.9067851;3.4380576;-0.0243015;8.0000000;0.0000000 +323.9338473;13.6627167;2.8488224;3.4333661;-0.0226220;8.0000000;0.0000000 +324.1338064;13.4710868;2.7917278;3.4290106;-0.0209429;8.0000000;0.0000000 +324.3337656;13.2792106;2.7354335;3.4249909;-0.0192613;8.0000000;0.0000000 +324.5337247;13.0871248;2.6798804;3.4213076;-0.0175795;8.0000000;0.0000000 +324.7336839;12.8948440;2.6250025;3.4179608;-0.0158927;8.0000000;0.0000000 +324.9336431;12.7023872;2.5707352;3.4149522;-0.0141992;8.0000000;0.0000000 +325.1336022;12.5097844;2.5170167;3.4122823;-0.0125057;8.0000000;0.0000000 +325.3335614;12.3170374;2.4637769;3.4099526;-0.0107948;8.0000000;0.0000000 +325.5335206;12.1241829;2.4109552;3.4079653;-0.0090826;8.0000000;0.0000000 +325.7334797;11.9312315;2.3584834;3.4063204;-0.0073680;8.0000000;0.0000000 +325.9334389;11.7382001;2.3062953;3.4050188;-0.0056504;8.0000000;0.0000000 +326.1333981;11.5451184;2.2543275;3.4040608;-0.0039323;8.0000000;0.0000000 +326.3333572;11.3519847;2.2025108;3.4034126;-0.0025673;8.0000000;0.0000000 +326.5333164;11.1588308;2.1507949;3.4030340;-0.0012197;8.0000000;0.0000000 +326.7332756;10.9656646;2.0991270;3.4029026;-0.0003623;8.0000000;0.0000000 +326.9332347;10.7724917;2.0474734;3.4028569;-0.0000952;8.0000000;0.0000000 +327.1331939;10.5793200;1.9958241;3.4028645;0.0001718;8.0000000;0.0000000 +327.3331531;10.3861479;1.9441693;3.4029001;0.0001725;8.0000000;0.0000000 +327.5331122;10.1929777;1.8925078;3.4029335;0.0001608;8.0000000;0.0000000 +327.7330714;9.9998090;1.8408401;3.4029645;0.0001497;8.0000000;0.0000000 +327.9330306;9.8066419;1.7891666;3.4029934;0.0001393;8.0000000;0.0000000 +328.1329897;9.6134764;1.7374878;3.4030202;0.0001288;8.0000000;0.0000000 +328.3329489;9.4203120;1.6858039;3.4030452;0.0001213;8.0000000;0.0000000 +328.5329080;9.2271490;1.6341154;3.4030687;0.0001139;8.0000000;0.0000000 +328.7328672;9.0339871;1.5824224;3.4030907;0.0001072;8.0000000;0.0000000 +328.9328264;8.8408263;1.5307254;3.4031116;0.0001011;8.0000000;0.0000000 +329.1327855;8.6476667;1.4790244;3.4031312;0.0000951;8.0000000;0.0000000 +329.3327447;8.4545079;1.4273197;3.4031496;0.0000895;8.0000000;0.0000000 +329.5327039;8.2613501;1.3756116;3.4031670;0.0000839;8.0000000;0.0000000 +329.7326630;8.0681932;1.3239002;3.4031832;0.0000785;8.0000000;0.0000000 +329.9326222;7.8750370;1.2721859;3.4031984;0.0000734;8.0000000;0.0000000 +330.1325814;7.6818817;1.2204686;3.4032125;0.0000682;8.0000000;0.0000000 +330.3325405;7.4887270;1.1687488;3.4032257;0.0000635;8.0000000;0.0000000 +330.5324997;7.2955730;1.1170265;3.4032379;0.0000588;8.0000000;0.0000000 +330.7324589;7.1024196;1.0653019;3.4032492;0.0000543;8.0000000;0.0000000 +330.9324180;6.9092667;1.0135752;3.4032596;0.0000500;8.0000000;0.0000000 +331.1323772;6.7161145;0.9618466;3.4032692;0.0000457;8.0000000;0.0000000 +331.3323364;6.5229626;0.9101162;3.4032780;0.0000419;8.0000000;0.0000000 +331.5322955;6.3298112;0.8583842;3.4032859;0.0000381;8.0000000;0.0000000 +331.7322547;6.1366602;0.8066508;3.4032932;0.0000345;8.0000000;0.0000000 +331.9322138;5.9435095;0.7549160;3.4032997;0.0000311;8.0000000;0.0000000 +332.1321730;5.7503592;0.7031800;3.4033056;0.0000278;8.0000000;0.0000000 +332.3321322;5.5572091;0.6514429;3.4033109;0.0000249;8.0000000;0.0000000 +332.5320913;5.3640593;0.5997049;3.4033156;0.0000220;8.0000000;0.0000000 +332.7320505;5.1709097;0.5479660;3.4033197;0.0000194;8.0000000;0.0000000 +332.9320097;4.9777604;0.4962264;3.4033234;0.0000171;8.0000000;0.0000000 +333.1319688;4.7846112;0.4444861;3.4033265;0.0000147;8.0000000;0.0000000 +333.3319280;4.5914621;0.3927452;3.4033293;0.0000129;8.0000000;0.0000000 +333.5318872;4.3983133;0.3410038;3.4033317;0.0000112;8.0000000;0.0000000 +333.7318463;4.2051645;0.2892620;3.4033338;0.0000097;8.0000000;0.0000000 +333.9318055;4.0120158;0.2375199;3.4033356;0.0000085;8.0000000;0.0000000 +334.1317647;3.8188672;0.1857774;3.4033372;0.0000073;8.0000000;0.0000000 +334.3317238;3.6257187;0.1340346;3.4033386;0.0000067;8.0000000;0.0000000 +334.5316830;3.4325702;0.0822915;3.4033399;0.0000062;8.0000000;0.0000000 +334.7316422;3.2394218;0.0305483;3.4033411;0.0000060;8.0000000;0.0000000 +334.9316013;3.0462735;-0.0211953;3.4033423;0.0000062;8.0000000;0.0000000 +335.1315605;2.8531252;-0.0729390;3.4033435;0.0000063;8.0000000;0.0000000 +335.3315197;2.6599770;-0.1246830;3.4033449;0.0000072;8.0000000;0.0000000 +335.5314788;2.4668289;-0.1764273;3.4033464;0.0000081;8.0000000;0.0000000 +335.7314380;2.2736809;-0.2281719;3.4033481;0.0000094;8.0000000;0.0000000 +335.9313971;2.0805329;-0.2799168;3.4033502;0.0000111;8.0000000;0.0000000 +336.1313563;1.8873851;-0.3316622;3.4033526;0.0000128;8.0000000;0.0000000 +336.3313155;1.6942374;-0.3834081;3.4033554;0.0000153;8.0000000;0.0000000 +336.5312746;1.5010899;-0.4351546;3.4033587;0.0000179;8.0000000;0.0000000 +336.7312338;1.3079426;-0.4869018;3.4033626;0.0000209;8.0000000;0.0000000 +336.9311930;1.1147954;-0.5386497;3.4033671;0.0000244;8.0000000;0.0000000 +337.1311521;0.9216485;-0.5903987;3.4033723;0.0000278;8.0000000;0.0000000 +337.3311113;0.7285020;-0.6421487;3.4033783;0.0000322;8.0000000;0.0000000 +337.5310705;0.5353557;-0.6938999;3.4033852;0.0000366;8.0000000;0.0000000 +337.7310296;0.3422098;-0.7456526;3.4033930;0.0000416;8.0000000;0.0000000 +337.9309888;0.1490644;-0.7974068;3.4034019;0.0000471;8.0000000;0.0000000 +338.1309480;-0.0440806;-0.8491629;3.4034118;0.0000525;8.0000000;0.0000000 From 63720d84839c4376a0625c6d16c66b32109de463 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Thu, 28 Sep 2023 18:56:43 -0400 Subject: [PATCH 28/32] Fix bug on unix platforms. --- gym/f110_gym/envs/track.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gym/f110_gym/envs/track.py b/gym/f110_gym/envs/track.py index 39c05e48..2bb99400 100644 --- a/gym/f110_gym/envs/track.py +++ b/gym/f110_gym/envs/track.py @@ -137,7 +137,7 @@ def find_track_dir(track_name): if tracks_r.status_code == 404: raise FileNotFoundError(f"No maps exists for {track_name}.") - tempdir = tempfile.gettempdir() + tempdir = tempfile.gettempdir() + "/" with open(tempdir + track_name + ".tar.xz", "wb") as f: f.write(tracks_r.content) From 454eff7ff39218b13107bd0c4faf94ead99af6b5 Mon Sep 17 00:00:00 2001 From: luigiberducci Date: Fri, 6 Oct 2023 12:06:01 +0200 Subject: [PATCH 29/32] remove script which do not contain any test --- tests/pyglet_test_.py | 207 ------------------------------------ tests/pyglet_test_camera.py | 128 ---------------------- 2 files changed, 335 deletions(-) delete mode 100644 tests/pyglet_test_.py delete mode 100644 tests/pyglet_test_camera.py diff --git a/tests/pyglet_test_.py b/tests/pyglet_test_.py deleted file mode 100644 index a05331e4..00000000 --- a/tests/pyglet_test_.py +++ /dev/null @@ -1,207 +0,0 @@ -# flake8: noqa -import argparse - -import numpy as np -import pyglet -import yaml -from PIL import Image -from pyglet import graphics, window -from pyglet.gl import * - - -class Camera: - """A simple 2D camera that contains the speed and offset.""" - - def __init__( - self, window: pyglet.window.Window, scroll_speed=1, min_zoom=1, max_zoom=4 - ): - assert ( - min_zoom <= max_zoom - ), "Minimum zoom must not be greater than maximum zoom" - self._window = window - self.scroll_speed = scroll_speed - self.max_zoom = max_zoom - self.min_zoom = min_zoom - self.offset_x = 0 - self.offset_y = 0 - self._zoom = max(min(1, self.max_zoom), self.min_zoom) - - @property - def zoom(self): - return self._zoom - - @zoom.setter - def zoom(self, value): - """Here we set zoom, clamp value to minimum of min_zoom and max of max_zoom.""" - self._zoom = max(min(value, self.max_zoom), self.min_zoom) - - @property - def position(self): - """Query the current offset.""" - return self.offset_x, self.offset_y - - @position.setter - def position(self, value): - """Set the scroll offset directly.""" - self.offset_x, self.offset_y = value - - def move(self, axis_x, axis_y): - """Move axis direction with scroll_speed. - Example: Move left -> move(-1, 0) - """ - self.offset_x += self.scroll_speed * axis_x - self.offset_y += self.scroll_speed * axis_y - - def begin(self): - # Set the current camera offset so you can draw your scene. - - # Translate using the offset. - view_matrix = self._window.view.translate( - -self.offset_x * self._zoom, -self.offset_y * self._zoom, 0 - ) - # Scale by zoom level. - view_matrix = view_matrix.scale(self._zoom, self._zoom, 1) - - self._window.view = view_matrix - - def end(self): - # Since this is a matrix, you will need to reverse the translate after rendering otherwise - # it will multiply the current offset every draw update pushing it further and further away. - - # Reverse scale, since that was the last transform. - view_matrix = self._window.view.scale(1 / self._zoom, 1 / self._zoom, 1) - # Reverse translate. - view_matrix = view_matrix.translate( - self.offset_x * self._zoom, self.offset_y * self._zoom, 0 - ) - - self._window.view = view_matrix - - def __enter__(self): - self.begin() - - def __exit__(self, exception_type, exception_value, traceback): - self.end() - - -class CenteredCamera(Camera): - """A simple 2D camera class. 0, 0 will be the center of the screen, as opposed to the bottom left.""" - - def begin(self): - x = -self._window.width // 2 / self._zoom + self.offset_x - y = -self._window.height // 2 / self._zoom + self.offset_y - - view_matrix = self._window.view.translate(-x * self._zoom, -y * self._zoom, 0) - view_matrix = view_matrix.scale(self._zoom, self._zoom, 1) - self._window.view = view_matrix - - def end(self): - x = -self._window.width // 2 / self._zoom + self.offset_x - y = -self._window.height // 2 / self._zoom + self.offset_y - - view_matrix = self._window.view.scale(1 / self._zoom, 1 / self._zoom, 1) - view_matrix = view_matrix.translate(x * self._zoom, y * self._zoom, 0) - self._window.view = view_matrix - - -parser = argparse.ArgumentParser() -parser.add_argument( - "--map_path", type=str, required=True, help="Path to the map without extensions" -) -parser.add_argument( - "--map_ext", type=str, required=True, help="Extension of the map image file" -) -args = parser.parse_args() - -# load map yaml -with open(args.map_path + ".yaml", "r") as yaml_stream: - try: - map_metada = yaml.safe_load(yaml_stream) - map_resolution = map_metada["resolution"] - origin = map_metada["origin"] - origin_x = origin[0] - origin_y = origin[1] - except yaml.YAMLError as ex: - print(ex) - -# load map image -map_img = np.array( - Image.open(args.map_path + args.map_ext).transpose(Image.FLIP_TOP_BOTTOM) -).astype(np.float64) -map_height = map_img.shape[0] -map_width = map_img.shape[1] - -# convert map pixels to coordinates -range_x = np.arange(map_width) -range_y = np.arange(map_height) -map_x, map_y = np.meshgrid(range_x, range_y) -map_x = (map_x * map_resolution + origin_x).flatten() -map_y = (map_y * map_resolution + origin_y).flatten() -map_z = np.zeros(map_y.shape) -map_coords = np.vstack((map_x, map_y, map_z)) - -# mask and only leave the obstacle points -map_mask = map_img == 0.0 -map_mask_flat = map_mask.flatten() -map_points = map_coords[:, map_mask_flat].T - -# prep opengl -try: - # Try and create a window with multisampling (antialiasing) - config = Config( - sample_buffers=1, - samples=4, - depth_size=16, - double_buffer=True, - ) - window = window.Window(resizable=True, config=config) -except window.NoSuchConfigException: - # Fall back to no multisampling for old hardware - window = window.Window(resizable=True) - -glClearColor(18 / 255, 4 / 255, 88 / 255, 1.0) -glEnable(GL_DEPTH_TEST) -glTranslatef(25, -5, -60) - -cam = Camera(window) - - -@window.event -def on_resize(width, height): - # Override the default on_resize handler to create a 3D projection - glViewport(0, 0, width, height) - glMatrixMode(GL_PROJECTION) - glLoadIdentity() - gluPerspective(60.0, width / float(height), 0.1, 1000.0) - glMatrixMode(GL_MODELVIEW) - return pyglet.event.EVENT_HANDLED - - -batch = graphics.Batch() - -points = [] -for i in range(map_points.shape[0]): - particle = batch.add( - 1, - GL_POINTS, - None, - ("v3f/stream", [map_points[i, 0], map_points[i, 1], map_points[i, 2]]), - ) - points.append(particle) - - -def loop(dt): - print(pyglet.clock.get_fps()) - - -@window.event -def on_draw(): - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT) - glColor3f(254 / 255, 117 / 255, 254 / 255) - cam.begin() - batch.draw() - cam.end() - - -pyglet.clock.schedule(loop) -pyglet.app.run() diff --git a/tests/pyglet_test_camera.py b/tests/pyglet_test_camera.py deleted file mode 100644 index 026e1ab1..00000000 --- a/tests/pyglet_test_camera.py +++ /dev/null @@ -1,128 +0,0 @@ -# flake8: noqa -import pyglet -from pyglet.gl import * - -# Zooming constants -ZOOM_IN_FACTOR = 1.2 -ZOOM_OUT_FACTOR = 1 / ZOOM_IN_FACTOR - - -class App(pyglet.window.Window): - def __init__(self, width, height, *args, **kwargs): - conf = Config(sample_buffers=1, samples=4, depth_size=16, double_buffer=True) - super().__init__(width, height, config=conf, *args, **kwargs) - - # Initialize camera values - self.left = 0 - self.right = width - self.bottom = 0 - self.top = height - self.zoom_level = 1 - self.zoomed_width = width - self.zoomed_height = height - - def init_gl(self, width, height): - # Set clear color - glClearColor(0 / 255, 0 / 255, 0 / 255, 0 / 255) - - # Set antialiasing - glEnable(GL_LINE_SMOOTH) - glEnable(GL_POLYGON_SMOOTH) - glHint(GL_LINE_SMOOTH_HINT, GL_NICEST) - - # Set alpha blending - glEnable(GL_BLEND) - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA) - - # Set viewport - glViewport(0, 0, width, height) - - def on_resize(self, width, height): - super().on_resize(width, height) - size = self.get_size() - self.left = 0 - self.right = size[0] - self.bottom = 0 - self.top = size[1] - self.zoomed_width = size[0] - self.zoomed_height = size[1] - - # # Set window values - # self.width = width - # self.height = height - # # Initialize OpenGL context - # self.init_gl(width, height) - # self.width = width - # self.height = height - # pass - - def on_mouse_drag(self, x, y, dx, dy, buttons, modifiers): - # Move camera - self.left -= dx * self.zoom_level - self.right -= dx * self.zoom_level - self.bottom -= dy * self.zoom_level - self.top -= dy * self.zoom_level - - def on_mouse_scroll(self, x, y, dx, dy): - # Get scale factor - f = ZOOM_IN_FACTOR if dy > 0 else ZOOM_OUT_FACTOR if dy < 0 else 1 - # If zoom_level is in the proper range - if 0.2 < self.zoom_level * f < 5: - self.zoom_level *= f - - size = self.get_size() - - mouse_x = x / size[0] - mouse_y = y / size[1] - - mouse_x_in_world = self.left + mouse_x * self.zoomed_width - mouse_y_in_world = self.bottom + mouse_y * self.zoomed_height - - self.zoomed_width *= f - self.zoomed_height *= f - - self.left = mouse_x_in_world - mouse_x * self.zoomed_width - self.right = mouse_x_in_world + (1 - mouse_x) * self.zoomed_width - self.bottom = mouse_y_in_world - mouse_y * self.zoomed_height - self.top = mouse_y_in_world + (1 - mouse_y) * self.zoomed_height - - def on_draw(self): - # Initialize Projection matrix - glMatrixMode(GL_PROJECTION) - glLoadIdentity() - - # Initialize Modelview matrix - glMatrixMode(GL_MODELVIEW) - glLoadIdentity() - # Save the default modelview matrix - glPushMatrix() - - # Clear window with ClearColor - glClear(GL_COLOR_BUFFER_BIT) - - # Set orthographic projection matrix - glOrtho(self.left, self.right, self.bottom, self.top, 1, -1) - - # Draw quad - glBegin(GL_QUADS) - glColor3ub(0xFF, 0, 0) - glVertex2i(10, 10) - - glColor3ub(0xFF, 0xFF, 0) - glVertex2i(110, 10) - - glColor3ub(0, 0xFF, 0) - glVertex2i(110, 110) - - glColor3ub(0, 0, 0xFF) - glVertex2i(10, 110) - glEnd() - - # Remove default modelview matrix - glPopMatrix() - - def run(self): - pyglet.app.run() - - -App(800, 800, resizable=True).run() From 389e94af8da0ac761ac42da30d11df6fad9cf771 Mon Sep 17 00:00:00 2001 From: luigiberducci Date: Fri, 6 Oct 2023 12:08:07 +0200 Subject: [PATCH 30/32] remove duplicate utilities which shadow actual utilities to test --- tests/test_collision_checks.py | 239 +-------------------------------- 1 file changed, 6 insertions(+), 233 deletions(-) diff --git a/tests/test_collision_checks.py b/tests/test_collision_checks.py index 00aeb4cf..88e4b4fc 100644 --- a/tests/test_collision_checks.py +++ b/tests/test_collision_checks.py @@ -1,4 +1,10 @@ # MIT License +import time +import unittest + +import numpy as np +from f110_gym.envs.collision_models import get_vertices, collision + # Copyright (c) 2020 Joseph Auckley, Matthew O'Kelly, Aman Sinha, Hongrui Zheng @@ -20,236 +26,6 @@ # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE # SOFTWARE. -""" -Prototype of Utility functions and GJK algorithm for Collision checks between vehicles -Originally from https://github.com/kroitor/gjk.c -Author: Hongrui Zheng -""" - -import unittest -import time -import numpy as np -from numba import njit - - -@njit(cache=True) -def perpendicular(pt): - """ - Return a 2-vector's perpendicular vector - - Args: - pt (np.ndarray, (2,)): input vector - - Returns: - pt (np.ndarray, (2,)): perpendicular vector - """ - temp = pt[0] - pt[0] = pt[1] - pt[1] = -1 * temp - return pt - - -@njit(cache=True) -def tripleProduct(a, b, c): - """ - Return triple product of three vectors - - Args: - a, b, c (np.ndarray, (2,)): input vectors - - Returns: - (np.ndarray, (2,)): triple product - """ - ac = a.dot(c) - bc = b.dot(c) - return b * ac - a * bc - - -@njit(cache=True) -def avgPoint(vertices): - """ - Return the average point of multiple vertices - - Args: - vertices (np.ndarray, (n, 2)): the vertices we want to find avg on - - Returns: - avg (np.ndarray, (2,)): average point of the vertices - """ - return np.sum(vertices, axis=0) / vertices.shape[0] - - -@njit(cache=True) -def indexOfFurthestPoint(vertices, d): - """ - Return the index of the vertex furthest away along a direction in the list of vertices - - Args: - vertices (np.ndarray, (n, 2)): the vertices we want to find avg on - - Returns: - idx (int): index of the furthest point - """ - return np.argmax(vertices.dot(d)) - - -@njit(cache=True) -def support(vertices1, vertices2, d): - """ - Minkowski sum support function for GJK - - Args: - vertices1 (np.ndarray, (n, 2)): vertices of the first body - vertices2 (np.ndarray, (n, 2)): vertices of the second body - d (np.ndarray, (2, )): direction to find the support along - - Returns: - support (np.ndarray, (n, 2)): Minkowski sum - """ - i = indexOfFurthestPoint(vertices1, d) - j = indexOfFurthestPoint(vertices2, -d) - return vertices1[i] - vertices2[j] - - -@njit(cache=True) -def collision(vertices1, vertices2): - """ - GJK test to see whether two bodies overlap - - Args: - vertices1 (np.ndarray, (n, 2)): vertices of the first body - vertices2 (np.ndarray, (n, 2)): vertices of the second body - - Returns: - overlap (boolean): True if two bodies collide - """ - index = 0 - simplex = np.empty((3, 2)) - - position1 = avgPoint(vertices1) - position2 = avgPoint(vertices2) - - d = position1 - position2 - - if d[0] == 0 and d[1] == 0: - d[0] = 1.0 - - a = support(vertices1, vertices2, d) - simplex[index, :] = a - - if d.dot(a) <= 0: - return False - - d = -a - - iter_count = 0 - while iter_count < 1e3: - a = support(vertices1, vertices2, d) - index += 1 - simplex[index, :] = a - if d.dot(a) <= 0: - return False - - ao = -a - - if index < 2: - b = simplex[0, :] - ab = b - a - d = tripleProduct(ab, ao, ab) - if np.linalg.norm(d) < 1e-10: - d = perpendicular(ab) - continue - - b = simplex[1, :] - c = simplex[0, :] - ab = b - a - ac = c - a - - acperp = tripleProduct(ab, ac, ac) - - if acperp.dot(ao) >= 0: - d = acperp - else: - abperp = tripleProduct(ac, ab, ab) - if abperp.dot(ao) < 0: - return True - simplex[0, :] = simplex[1, :] - d = abperp - - simplex[1, :] = simplex[2, :] - index -= 1 - - iter_count += 1 - return False - - -""" -Utility functions for getting vertices by pose and shape -""" - - -@njit(cache=True) -def get_trmtx(pose): - """ - Get transformation matrix of vehicle frame -> global frame - - Args: - pose (np.ndarray (3, )): current pose of the vehicle - - return: - H (np.ndarray (4, 4)): transformation matrix - """ - x = pose[0] - y = pose[1] - th = pose[2] - cos = np.cos(th) - sin = np.sin(th) - - H = np.array( - [ - [cos, -sin, 0.0, x], - [sin, cos, 0.0, y], - [0.0, 0.0, 1.0, 0.0], - [0.0, 0.0, 0.0, 1.0], - ] - ) - return H - - -@njit(cache=True) -def get_vertices(pose, length, width): - """ - Utility function to return vertices of the car body given pose and size - - Args: - pose (np.ndarray, (3, )): current world coordinate pose of the vehicle - length (float): car length - width (float): car width - - Returns: - vertices (np.ndarray, (4, 2)): corner vertices of the vehicle body - """ - H = get_trmtx(pose) - rl = H.dot(np.asarray([[-length / 2], [width / 2], [0.0], [1.0]])).flatten() - rr = H.dot(np.asarray([[-length / 2], [-width / 2], [0.0], [1.0]])).flatten() - fl = H.dot(np.asarray([[length / 2], [width / 2], [0.0], [1.0]])).flatten() - fr = H.dot(np.asarray([[length / 2], [-width / 2], [0.0], [1.0]])).flatten() - rl = rl / rl[3] - rr = rr / rr[3] - fl = fl / fl[3] - fr = fr / fr[3] - - vertices = np.asarray( - [[rl[0], rl[1]], [rr[0], rr[1]], [fr[0], fr[1]], [fl[0], fl[1]]] - ) - return vertices - - -""" -Unit test for GJK collision checks -Author: Hongrui Zheng -""" - class CollisionTests(unittest.TestCase): def setUp(self): @@ -307,6 +83,3 @@ def test_fps(self): print("gjk fps:", fps) # self.assertGreater(fps, 500) This is a platform dependent test, not ideal. - -if __name__ == "__main__": - unittest.main() From c9363c8309dfb1cef56431b2771563a1bc8e1410 Mon Sep 17 00:00:00 2001 From: luigiberducci Date: Fri, 6 Oct 2023 12:10:31 +0200 Subject: [PATCH 31/32] remove duplicate utilities which shadow actual utilities to test --- tests/test_scan_sim.py | 274 ----------------------------------------- 1 file changed, 274 deletions(-) diff --git a/tests/test_scan_sim.py b/tests/test_scan_sim.py index bb79b26d..6883385b 100644 --- a/tests/test_scan_sim.py +++ b/tests/test_scan_sim.py @@ -30,230 +30,6 @@ import numpy as np from f110_gym.envs.laser_models import ScanSimulator2D -from numba import njit -from scipy.ndimage import distance_transform_edt as edt - - -def get_dt(bitmap, resolution): - """ - Distance transformation, returns the distance matrix from the input bitmap. - Uses scipy.ndimage, cannot be JITted. - - Args: - bitmap (numpy.ndarray, (n, m)): input binary bitmap of the environment, where 0 is obstacles, and 255 (or anything > 0) is freespace - resolution (float): resolution of the input bitmap (m/cell) - - Returns: - dt (numpy.ndarray, (n, m)): output distance matrix, where each cell has the corresponding distance (in meters) to the closest obstacle - """ - dt = resolution * edt(bitmap) - return dt - - -@njit(cache=True) -def xy_2_rc(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution): - """ - Translate (x, y) coordinate into (r, c) in the matrix - - Args: - x (float): coordinate in x (m) - y (float): coordinate in y (m) - orig_x (float): x coordinate of the map origin (m) - orig_y (float): y coordinate of the map origin (m) - - Returns: - r (int): row number in the transform matrix of the given point - c (int): column number in the transform matrix of the given point - """ - # translation - x_trans = x - orig_x - y_trans = y - orig_y - - # rotation - x_rot = x_trans * orig_c + y_trans * orig_s - y_rot = -x_trans * orig_s + y_trans * orig_c - - # clip the state to be a cell - if ( - x_rot < 0 - or x_rot >= width * resolution - or y_rot < 0 - or y_rot >= height * resolution - ): - c = -1 - r = -1 - else: - c = int(x_rot / resolution) - r = int(y_rot / resolution) - - return r, c - - -@njit(cache=True) -def distance_transform( - x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt -): - """ - Look up corresponding distance in the distance matrix - - Args: - x (float): x coordinate of the lookup point - y (float): y coordinate of the lookup point - orig_x (float): x coordinate of the map origin (m) - orig_y (float): y coordinate of the map origin (m) - - Returns: - distance (float): corresponding shortest distance to obstacle in meters - """ - r, c = xy_2_rc(x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution) - distance = dt[r, c] - return distance - - -@njit(cache=True) -def trace_ray( - x, - y, - theta_index, - sines, - cosines, - eps, - orig_x, - orig_y, - orig_c, - orig_s, - height, - width, - resolution, - dt, - max_range, -): - """ - Find the length of a specific ray at a specific scan angle theta - Purely math calculation and loops, should be JITted. - - Args: - x (float): current x coordinate of the ego (scan) frame - y (float): current y coordinate of the ego (scan) frame - theta_index(int): current index of the scan beam in the scan range - sines (numpy.ndarray (n, )): pre-calculated sines of the angle array - cosines (numpy.ndarray (n, )): pre-calculated cosines ... - - Returns: - total_distance (float): the distance to first obstacle on the current scan beam - """ - - # int casting, and index precal trigs - theta_index_ = int(theta_index) - s = sines[theta_index_] - c = cosines[theta_index_] - - # distance to nearest initialization - dist_to_nearest = distance_transform( - x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt - ) - total_dist = dist_to_nearest - - # ray tracing iterations - while dist_to_nearest > eps and total_dist <= max_range: - # move in the direction of the ray by dist_to_nearest - x += dist_to_nearest * c - y += dist_to_nearest * s - - # update dist_to_nearest for current point on ray - # also keeps track of total ray length - dist_to_nearest = distance_transform( - x, y, orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt - ) - total_dist += dist_to_nearest - - return total_dist - - -@njit(cache=True) -def get_scan( - pose, - theta_dis, - fov, - num_beams, - theta_index_increment, - sines, - cosines, - eps, - orig_x, - orig_y, - orig_c, - orig_s, - height, - width, - resolution, - dt, - max_range, -): - """ - Perform the scan for each discretized angle of each beam of the laser, loop heavy, should be JITted - - Args: - pose (numpy.ndarray(3, )): current pose of the scan frame in the map - theta_dis (int): number of steps to discretize the angles between 0 and 2pi for look up - fov (float): field of view of the laser scan - num_beams (int): number of beams in the scan - theta_index_increment (float): increment between angle indices after discretization - - Returns: - scan (numpy.ndarray(n, )): resulting laser scan at the pose, n=num_beams - """ - # empty scan array init - scan = np.empty((num_beams,)) - - # make theta discrete by mapping the range [-pi, pi] onto [0, theta_dis] - theta_index = theta_dis * (pose[2] - fov / 2.0) / (2.0 * np.pi) - - # make sure it's wrapped properly - theta_index = np.fmod(theta_index, theta_dis) - while theta_index < 0: - theta_index += theta_dis - - # sweep through each beam - for i in range(0, num_beams): - # trace the current beam - scan[i] = trace_ray( - pose[0], - pose[1], - theta_index, - sines, - cosines, - eps, - orig_x, - orig_y, - orig_c, - orig_s, - height, - width, - resolution, - dt, - max_range, - ) - - # increment the beam index - theta_index += theta_index_increment - - # make sure it stays in the range [0, theta_dis) - while theta_index >= theta_dis: - theta_index -= theta_dis - - return scan - - -""" -Unit test for the 2D scan simulator class -Author: Hongrui Zheng - -Test cases: - 1, 2: Comparison between generated scan array of the new simulator and the legacy C++ simulator, - generated data used, MSE is used as the metric - 2. FPS test, should be greater than 500 -""" class ScanTests(unittest.TestCase): @@ -337,53 +113,3 @@ def test_fps(self): fps = 10000 / (end - start) self.assertGreater(fps, 500.0) - - -def main(): - num_beams = 1080 - fov = 4.7 - # map_path = '../envs/maps/Berlin_map.yaml' - scan_rng = np.random.default_rng(seed=12345) - scan_sim = ScanSimulator2D(num_beams, fov) - scan_sim.set_map(map_name="Example") - scan_sim.scan(np.array([0.0, 0.0, 0.0])) - - # fps test - import time - - start = time.time() - for i in range(10000): - x_test = i / 10000 - scan_sim.scan(np.array([x_test, 0.0, 0.0]), rng=scan_rng) - end = time.time() - fps = (end - start) / 10000 - print("FPS test") - print("Elapsed time: " + str(end - start) + " , FPS: " + str(1 / fps)) - - # visualization - import matplotlib.pyplot as plt - from matplotlib.animation import FuncAnimation - - num_iter = 100 - theta = np.linspace(-fov / 2.0, fov / 2.0, num=num_beams) - fig = plt.figure() - ax = fig.add_subplot(111, projection="polar") - ax.set_ylim(0, 70) - (line,) = ax.plot([], [], ".", lw=0) - - def update(i): - # x_ani = i * 3. / num_iter - theta_ani = -i * 2 * np.pi / num_iter - x_ani = 0.0 - current_scan = scan_sim.scan(np.array([x_ani, 0.0, theta_ani])) - print(np.max(current_scan)) - line.set_data(theta, current_scan) - return (line,) - - FuncAnimation(fig, update, frames=num_iter, blit=True) - plt.show() - - -if __name__ == "__main__": - # test.main() - main() From bc3d6f2d761da4b0667a06c528795b6268e9a1b5 Mon Sep 17 00:00:00 2001 From: nandantumu Date: Fri, 20 Oct 2023 15:13:48 -0400 Subject: [PATCH 32/32] Changes requested to PR #81: - Removing Spielberg - Removing __del__ from f110_env --- gym/f110_gym/envs/f110_env.py | 5 - .../Spielberg_DonkeySim_waypoints.txt | 864 --------- .../maps/Spielberg/Spielberg_centerline.csv | 865 --------- gym/f110_gym/maps/Spielberg/Spielberg_map.png | Bin 62176 -> 0 bytes .../maps/Spielberg/Spielberg_map.yaml | 6 - .../maps/Spielberg/Spielberg_raceline.csv | 1695 ----------------- 6 files changed, 3435 deletions(-) delete mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt delete mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv delete mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_map.png delete mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_map.yaml delete mode 100644 gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv diff --git a/gym/f110_gym/envs/f110_env.py b/gym/f110_gym/envs/f110_env.py index 1a14fb4e..7353fe3c 100644 --- a/gym/f110_gym/envs/f110_env.py +++ b/gym/f110_gym/envs/f110_env.py @@ -176,11 +176,6 @@ def __init__(self, config: dict = None, render_mode=None, **kwargs): self.render_obs = None self.render_mode = render_mode - def __del__(self): - """ - Finalizer, does cleanup - """ - @classmethod def default_config(cls) -> dict: """ diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt b/gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt deleted file mode 100644 index 394a486d..00000000 --- a/gym/f110_gym/maps/Spielberg/Spielberg_DonkeySim_waypoints.txt +++ /dev/null @@ -1,864 +0,0 @@ -76.08812195356482,0.0,9.120088008544716 -75.70418495495521,0.0,9.016879535734098 -75.32024660388215,0.0,8.913676313663823 -74.93630793458243,0.0,8.810476751200465 -74.55236974262274,0.0,8.707278938983892 -74.1684328235698,0.0,8.60408128588066 -73.78449821166033,0.0,8.500882041643997 -73.40056662290442,0.0,8.39767937647043 -73.01663893242544,0.0,8.294471699226522 -72.63271593579009,0.0,8.191257498335517 -72.24879747388505,0.0,8.088036773797409 -71.86488330804029,0.0,7.984809764282204 -71.48097335869917,0.0,7.881576628903261 -71.09706738719163,0.0,7.778337526773916 -70.71316515484767,0.0,7.675092696564183 -70.32926642299729,0.0,7.5718424565007565 -69.94537103252715,0.0,7.468586806583637 -69.56147882432387,0.0,7.365326144596175 -69.17758955971746,0.0,7.262060550095057 -68.79370300003788,0.0,7.158790261750282 -68.40981898617183,0.0,7.05551543867521 -68.02593727944925,0.0,6.952236319539839 -67.64205772075682,0.0,6.84895322257088 -67.2581801509812,0.0,6.7456661477683095 -66.87430417233901,0.0,6.6423754133588355 -66.49042978483027,0.0,6.53908125801246 -66.10655674978494,0.0,6.43578376128586 -65.72268474897636,0.0,6.332483241405731 -65.33881370284784,0.0,6.2291798574854 -64.95494337272936,0.0,6.125873768638227 -64.57107351995091,0.0,6.02256529309089 -64.18720398539917,0.0,5.919254510400069 -63.803334530404086,0.0,5.815941738792448 -63.41946491629565,0.0,5.712627057824695 -63.03559506351721,0.0,5.609310785723501 -62.65172473339874,0.0,5.505993081602217 -62.26785360771354,0.0,5.402674104574179 -61.88398160690495,0.0,5.2993541728660745 -61.50010849230296,0.0,5.196033366034575 -61.116234025237546,0.0,5.092711922749703 -60.732358126152036,0.0,4.989390081681472 -60.34848039726305,0.0,4.886068001943226 -59.96460075901395,0.0,4.782745922204973 -59.580718972734715,0.0,4.679424081136742 -59.19683487931197,0.0,4.576102637851869 -58.81294824007574,0.0,4.472781751463705 -58.42905889591266,0.0,4.369461660642257 -58.04516652859604,0.0,4.266142604057548 -57.66127105856921,0.0,4.162824740822914 -57.27737224716215,0.0,4.059508389165048 -56.89346985570485,0.0,3.9561935490839506 -56.509563725083986,0.0,3.852880538806316 -56.125653616629506,0.0,3.749569597002144 -55.741739371228086,0.0,3.646260882784798 -55.357820750209704,0.0,3.542954634824275 -54.973897594461015,0.0,3.4396509326772655 -54.58996966531201,0.0,3.336350174127114 -54.20603672409267,0.0,3.2330523591738283 -53.822098611689654,0.0,3.1297578856007657 -53.438155089432925,0.0,3.026466832964598 -53.054205998209156,0.0,2.923179439935348 -52.67025117890502,0.0,2.819895865626351 -52.28629031329379,0.0,2.7166164282642944 -51.90232443561224,0.0,2.6133414460758786 -51.51835879660071,0.0,2.5100723510811864 -51.134399840349616,0.0,2.406810654856989 -50.75045393139273,0.0,2.303558028093403 -50.366527434263816,0.0,2.2003159028105213 -49.98262679305331,0.0,2.0970859496984575 -49.598758213181625,0.0,1.993869759890651 -49.21492821829585,0.0,1.890668765407196 -48.83114317292977,0.0,1.7874846369382071 -48.44740936206046,0.0,1.6843189656171216 -48.06373330933502,0.0,1.581173342577384 -47.68012122017389,0.0,1.4780491998390888 -47.29657953866746,0.0,1.3749482080923494 -46.91311256087606,0.0,1.2718706855638473 -46.52964542397132,0.0,1.168769534703765 -46.14600238726476,0.0,1.0655372744482108 -45.76200118642084,0.0,0.9620626845697249 -45.3774594775473,0.0,0.8582343061708269 -44.992195075865254,0.0,0.7539408394673828 -44.60602571703913,0.0,0.6490709051185775 -44.21907137253034,0.0,0.5437511573462448 -43.8359202347268,0.0,0.4416250530582708 -43.463249892893394,0.0,0.3477037874676654 -43.088186009025996,0.0,0.24749611276845407 -42.6912361642463,0.0,0.12588713640279714 -42.286127623639,0.0,0.024688822023767543 -41.894964890294396,0.0,0.0 -41.53795671136556,0.0,0.09980448148548327 -41.22166388692285,0.0,0.31365679367245214 -40.94666845357865,0.0,0.6055162525652165 -40.71349914497514,0.0,0.9392832226741117 -40.51764740495302,0.0,1.2878009544530808 -40.343783856166745,0.0,1.6431236457287843 -40.17517741226665,0.0,1.9997938679149394 -39.9981389953706,0.0,2.353288903764641 -39.81072750223833,0.0,2.7026963178066525 -39.61383794542989,0.0,3.0479752179115644 -39.40836509883534,0.0,3.389084711949959 -39.195204054571434,0.0,3.725983828235753 -38.97524958652823,0.0,4.058631754196212 -38.74939718460582,0.0,4.386988950165342 -38.51862181581965,0.0,4.71130100758964 -38.28407291496687,0.0,5.032435730647333 -38.046922510939474,0.0,5.3513427873321815 -37.808343030412836,0.0,5.6689720047512635 -37.56950658183561,0.0,5.9862731304549825 -37.331585432769835,0.0,6.304195911993769 -37.095733393629594,0.0,6.623675538047042 -36.86240688104219,0.0,6.945092528177021 -36.631164991931364,0.0,7.268114176381371 -36.40150779217025,0.0,7.592360917777945 -36.17293542718862,0.0,7.917452948814591 -35.94494804241624,0.0,8.243010625052488 -35.71704570372624,0.0,8.5686543816095 -35.488815909774274,0.0,8.89407060608457 -35.26019549256273,0.0,9.219210768907777 -35.031208637319956,0.0,9.544092452103635 -34.80187952927419,0.0,9.86873315813999 -34.57223235365374,0.0,10.193150469041345 -34.34229129568691,0.0,10.517361966832222 -34.11208046104529,0.0,10.841385233537137 -33.881624114513876,0.0,11.165237771623916 -33.650946441320926,0.0,11.488937242673758 -33.42007154713808,0.0,11.812501149154505 -33.18902369675028,0.0,12.135947073090668 -32.95782699582917,0.0,12.459292596506753 -32.726505709159696,0.0,12.782555221870611 -32.49508394241347,0.0,13.105752610763417 -32.26358596037547,0.0,13.428902345209696 -32.03203594827398,0.0,13.752021848120616 -31.800457932223942,0.0,14.07512878107735 -31.568876256566988,0.0,14.398240726104426 -31.33731502697475,0.0,14.721375265226351 -31.105798428675477,0.0,15.044549900910972 -30.874350726454196,0.0,15.367782215182796 -30.642995946425806,0.0,15.691089790066334 -30.411758432931947,0.0,16.0144902075861 -30.180662291644254,0.0,16.33800097020995 -29.949731707790995,0.0,16.661639739519053 -29.718990866600485,0.0,16.985424017981252 -29.488463873744315,0.0,17.30937146717774 -29.258236173088235,0.0,17.63353737899556 -29.028869116509924,0.0,17.95827228013156 -28.80114745102206,0.0,18.2840648872219 -28.57585711698738,0.0,18.61140487158276 -28.35378429343865,0.0,18.94078182497367 -28.135714920738636,0.0,19.272685339154165 -27.92243509836343,0.0,19.607605005883762 -27.714487800599457,0.0,19.945876952101706 -27.51138462903731,0.0,20.287186372056855 -27.312363669429132,0.0,20.63104558334981 -27.11666300752716,0.0,20.97696706269451 -26.92352056997023,0.0,21.324463127691565 -26.732174522067197,0.0,21.67304617549825 -26.541863506466967,0.0,22.022229080611858 -26.35204765159331,0.0,22.371664021262383 -26.162714626162064,0.0,22.72133564301212 -25.9739292688609,0.0,23.07127712099332 -25.785756418377517,0.0,23.42152155078151 -25.598260913399614,0.0,23.7721021870656 -25.41150751305817,0.0,24.12305220497782 -25.225561056040902,0.0,24.474404700093714 -25.040486381035457,0.0,24.82619292710219 -24.85634832672956,0.0,25.178449902022134 -24.673211652254196,0.0,25.5312089590991 -24.491141275853757,0.0,25.88450327346533 -24.31020187710255,0.0,26.23836586113971 -24.130458374244938,0.0,26.592829976811124 -23.951956989707362,0.0,26.947919248811157 -23.77466232077078,0.0,27.303615538218608 -23.59851637062132,0.0,27.659889170394816 -23.423461301558383,0.0,28.016710311587765 -23.2494391963248,0.0,28.374049446272146 -23.07639213766332,0.0,28.731876820252634 -22.90426220831673,0.0,29.090162679333893 -22.73299157058449,0.0,29.44887742843394 -22.562522227652686,0.0,29.807991313357448 -22.39279634182079,0.0,30.16747465946575 -22.223755995831574,0.0,30.527297792120194 -22.055343272427812,0.0,30.887431036682113 -21.887500333908967,0.0,31.24784463895619 -21.72016910390446,0.0,31.608508924303752 -21.553291903827095,0.0,31.969394218086148 -21.386810657306313,0.0,32.33047084566472 -21.220667526641556,0.0,32.69170913240082 -21.05480451501893,0.0,33.0530793240991 -20.889163864294574,0.0,33.41455174612091 -20.723687657211237,0.0,33.776096723827585 -20.55831789695506,0.0,34.137684582580476 -20.392996666268793,0.0,34.49928564774091 -20.22766612745191,0.0,34.860870165113575 -20.06226844280384,0.0,35.2224084600598 -19.896745535954054,0.0,35.58387085794094 -19.731039648758653,0.0,35.94522768411833 -19.56509278440373,0.0,36.30644918439663 -19.3988646076566,0.0,36.6675144353711 -19.232465702291336,0.0,37.02847801291876 -19.066084219837244,0.0,37.38943299834584 -18.899908789163646,0.0,37.750472950298615 -18.734128198253224,0.0,38.11169126831004 -18.5689310759753,0.0,38.473181511026375 -18.404506210312533,0.0,38.835037077980566 -18.24085765865521,0.0,39.19726584528313 -18.077126368058998,0.0,39.55947512120106 -17.912201011372645,0.0,39.92115510658013 -17.744970261444884,0.0,40.28179600226614 -17.574322870681137,0.0,40.64088808866151 -17.39914751193013,0.0,40.997921646168706 -17.21833261937062,0.0,41.35238623918016 -17.03064681483327,0.0,41.70349131304613 -16.83454558508774,0.0,42.04971288015763 -16.62843381886031,0.0,42.389408811247804 -16.410913068970437,0.0,42.721098477093946 -16.184332007489125,0.0,43.04638040990669 -15.954398427849469,0.0,43.36961344018856 -15.726886951089035,0.0,43.69521352013264 -15.504597494722432,0.0,44.02527108085255 -15.285801928720339,0.0,44.35833683845438 -15.068392319501271,0.0,44.6926647626576 -14.850260813040428,0.0,45.02650858451166 -14.62929931664295,0.0,45.358122353292714 -14.403399896727386,0.0,45.685759720493536 -14.17081707990991,0.0,46.00797275468361 -13.931560015207786,0.0,46.32475715980266 -13.686168335527249,0.0,46.63654492857965 -13.435181832887864,0.0,46.943768212856966 -13.179140378865831,0.0,47.24685908492023 -12.918583606367434,0.0,47.54624961705515 -12.654051307412182,0.0,47.84237212021738 -12.386083274019676,0.0,48.13565858713592 -12.115219298209446,0.0,48.426541169653106 -11.84199909244441,0.0,48.71545194005462 -11.566962528300806,0.0,49.002823129739454 -11.290649238684807,0.0,49.28908681099331 -11.013599015616037,0.0,49.57467513565848 -10.736348389290484,0.0,49.8600175506505 -10.459226008320186,0.0,50.14537953658382 -10.182234657188715,0.0,50.430769049125644 -9.90534840042092,0.0,50.7161716089617 -9.62854146165516,0.0,51.001572577664305 -9.351787905416288,0.0,51.286957316805825 -9.075061955342619,0.0,51.572311347071945 -8.798337675959047,0.0,51.85762003003502 -8.521589290903862,0.0,52.14286880682408 -8.244790944258668,0.0,52.42804303901147 -7.967916700548358,0.0,52.71312824728285 -7.69094078341125,0.0,52.99810979321066 -7.413837257372222,0.0,53.282973038367174 -7.136580346069593,0.0,53.56770358299478 -6.859143795801543,0.0,53.85228559531575 -6.5814974545894245,0.0,54.136693139855 -6.3036094202077635,0.0,54.420894473500425 -6.025447392647678,0.0,54.70485769402653 -5.746979151457069,0.0,54.98855089920784 -5.4681727148537504,0.0,55.27194234593223 -5.188995862385596,0.0,55.55500013197424 -4.909416373600351,0.0,55.837692514221715 -4.629402187159329,0.0,56.119987431335844 -4.348921082610261,0.0,56.401853219761165 -4.067940919057733,0.0,56.683257977272206 -3.786429555606162,0.0,56.96416980164351 -3.504354851360162,0.0,57.244556949762924 -3.2216847449808625,0.0,57.52438759896164 -2.938486223186075,0.0,57.80370630097602 -2.655110369569414,0.0,58.08277662706038 -2.37195878621111,0.0,58.36190113123837 -2.089433154748164,0.0,58.64138228797698 -1.8079349977041659,0.0,58.92152265129984 -1.527865996716102,0.0,59.202624775230575 -1.2496477225889464,0.0,59.4850177857213 -0.9751367893772596,0.0,59.770954329939826 -0.7085706241021796,0.0,60.06587791405492 -0.4544182432569528,0.0,60.37553181377537 -0.22565955654947345,0.0,60.70530106111595 -0.06008923392317911,0.0,61.059525790761285 -0.0,0.0,61.44235663340335 -0.08163055533233887,0.0,61.84022090257106 -0.3100769025455321,0.0,62.14836951050047 -0.6679514536325257,0.0,62.271529125960214 -1.0773922528139224,0.0,62.30272305838393 -1.4795477293130261,0.0,62.33598427092974 -1.874016837946229,0.0,62.37727800242136 -2.265436618898079,0.0,62.42497532999943 -2.6573098728803615,0.0,62.47740269951164 -3.0500586480380747,0.0,62.53276539199423 -3.443586839911461,0.0,62.58924824241866 -3.8377985031540334,0.0,62.6450361653131 -4.232597453749364,0.0,62.69831407520577 -4.6278876667943365,0.0,62.7472668070681 -5.023573435612519,0.0,62.790093277402605 -5.419583397869133,0.0,62.82588065295461 -5.815884855771969,0.0,62.855117013906934 -6.21244813468239,0.0,62.878413673727266 -6.609243798631738,0.0,62.89638202543996 -7.006242332094715,0.0,62.909633621182735 -7.4034143786593205,0.0,62.918779615309944 -7.800730263686916,0.0,62.92443163951596 -8.198160551208872,0.0,62.92720108682519 -8.595675805256505,0.0,62.92769919114862 -8.993246510304544,0.0,62.926537504623965 -9.390843150827664,0.0,62.92432742027563 -9.788436211300521,0.0,62.92168033112797 -10.185996255754517,0.0,62.919207630205335 -10.583496712261166,0.0,62.91747385165229 -10.980939808407285,0.0,62.91659101126305 -11.378343842227466,0.0,62.91641733904805 -11.775727111756268,0.0,62.916808439647625 -12.173108233254915,0.0,62.91761999725877 -12.570505584314652,0.0,62.91870745740843 -12.967937622083369,0.0,62.91992642473693 -13.365410949764886,0.0,62.920955172062634 -13.76287091192549,0.0,62.92055667269254 -14.160243361746872,0.0,62.91719874468049 -14.557453993297415,0.0,62.90934936519366 -14.954428500645427,0.0,62.89547643184251 -15.351092657415954,0.0,62.87404784223757 -15.747372237233996,0.0,62.84353292600943 -16.14324432777802,0.0,62.80383923830519 -16.538833673909743,0.0,62.759010246979656 -16.934291353749273,0.0,62.713827705803695 -17.329766695170008,0.0,62.67290701554711 -17.725371793522783,0.0,62.63718742227965 -18.12118246631602,0.0,62.60401809769 -18.517268802977746,0.0,62.570597214903486 -18.91341122709325,0.0,62.53398770070295 -19.30890828748545,0.0,62.4910281320562 -19.703013344787543,0.0,62.43853727631969 -20.09528947375687,0.0,62.374906895368866 -20.486206456541645,0.0,62.303130786327955 -20.87639891671445,0.0,62.22703984162412 -21.26642359186601,0.0,62.14999517153626 -21.6564216950891,0.0,62.072844452404624 -22.046395692640587,0.0,61.995598185709895 -22.43634805077729,0.0,61.91826623647944 -22.826281156199364,0.0,61.840858549297195 -23.21619747516364,0.0,61.763385068747226 -23.606099473926953,0.0,61.68585565985684 -23.995989539189466,0.0,61.60828026721002 -24.385870137208016,0.0,61.5306688353908 -24.77574373423942,0.0,61.4530311498698 -25.16561279654053,0.0,61.37537731434439 -25.55547963125482,0.0,61.297717114285206 -25.945346863752462,0.0,61.22006049427628 -26.335216801176976,0.0,61.14241747845827 -26.725091909785156,0.0,61.06479777274515 -27.11497465583384,0.0,60.987211480834276 -27.504867505579874,0.0,60.90966846775295 -27.894772766166746,0.0,60.83217859852856 -28.28469306296462,0.0,60.754751897301716 -28.674630703116996,0.0,60.67739814954312 -29.064588232437373,0.0,60.60012729983674 -29.45456803762592,0.0,60.52294937232328 -29.844572505382764,0.0,60.44587415247338 -30.234604101964784,0.0,60.36891158487103 -30.624665373185458,0.0,60.292071693656894 -31.014758626188275,0.0,60.2153642643017 -31.40488632723008,0.0,60.138799320946035 -31.79505062434101,0.0,60.062385296597185 -32.18524897170755,0.0,59.98611558805132 -32.57547643681604,0.0,59.90997436353078 -32.965727768926136,0.0,59.83394547303109 -33.3559979559675,0.0,59.75801300521789 -33.74628182675645,0.0,59.68216096920007 -34.13657428966597,0.0,59.60637329452992 -34.5268701735124,0.0,59.530633990316346 -34.91716446622538,0.0,59.4549269861116 -35.30745191706457,0.0,59.37923637058128 -35.6977275935163,0.0,59.30354607327769 -36.087986165283546,0.0,59.227840103309674 -36.47822262029597,0.0,59.1521024697862 -36.868431866926585,0.0,59.07631710225955 -37.25861820123565,0.0,59.00051399359502 -37.64881535525211,0.0,58.92486872536776 -38.0390630277553,0.0,58.84958536044145 -38.42940107663788,0.0,58.77486788212312 -38.819868962009174,0.0,58.70092043283316 -39.21050662131854,0.0,58.62794715499189 -39.601353514675274,0.0,58.55615211146305 -39.99244949997207,0.0,58.48573944466699 -40.38383411687489,0.0,58.41691313791077 -40.77554722327643,0.0,58.34987733361467 -41.16762843839934,0.0,58.28483617419917 -41.560117381466306,0.0,58.22199364297121 -41.95305383081329,0.0,58.16155396190787 -42.34646698373894,0.0,58.10369828155129 -42.74032414245106,0.0,58.04847274477126 -43.1345700150626,0.0,57.99587401018752 -43.52914923012985,0.0,57.94589881597656 -43.92400649576576,0.0,57.898543741201465 -44.31908636096995,0.0,57.85380536492529 -44.71433353385536,0.0,57.81168050488124 -45.10970704273592,0.0,57.77215197682811 -45.505213331702066,0.0,57.73515860168513 -45.90086831208818,0.0,57.700629653570914 -46.29668797478536,0.0,57.668494724830694 -46.69268831068466,0.0,57.63868332825311 -47.088885310677156,0.0,57.611124897070056 -47.48529480654058,0.0,57.58574854628682 -47.88191966231513,0.0,57.56243828227559 -48.27873831814269,0.0,57.540993860892925 -48.675726350124954,0.0,57.52120572986475 -49.072859573033625,0.0,57.50286433691703 -49.470113642527075,0.0,57.485760050218985 -49.867464373377004,0.0,57.469683397053274 -50.264887421241795,0.0,57.45442474558912 -50.662358521336486,0.0,57.439774702665815 -51.059853329319424,0.0,57.425523636452624 -51.45734765996234,0.0,57.41146191511881 -51.85481716892359,0.0,57.39738014550365 -52.252237670974864,0.0,57.383068616219745 -52.6495847422179,0.0,57.368317934106344 -53.0468361067845,0.0,57.35293111684359 -53.44399319669476,0.0,57.33686496515858 -53.84107303707653,0.0,57.32017858965861 -54.23809313039761,0.0,57.30293277164108 -54.6350708200125,0.0,57.285188292403404 -55.03202352883239,0.0,57.267006171913025 -55.428968679768445,0.0,57.24844711191069 -55.825923616175146,0.0,57.22957205280716 -56.222905840520355,0.0,57.21044177589981 -56.61993269615854,0.0,57.19111714204274 -57.01702160600091,0.0,57.17165901209006 -57.41418999295861,0.0,57.152128326452484 -57.81145520038615,0.0,57.13258578687082 -58.20883473075135,0.0,57.11309233375577 -58.60632516311732,0.0,57.09377963339951 -59.00385099820236,0.0,57.07502510265404 -59.401320825390286,0.0,57.0572595408983 -59.79864363184835,0.0,57.040913906624525 -60.19572808651707,0.0,57.02641899921166 -60.592483017450355,0.0,57.01420561803856 -60.9888166162487,0.0,57.00466892109512 -61.38456555306445,0.0,56.99356567372321 -61.77942464850382,0.0,56.96747100574842 -62.17307201627186,0.0,56.91188030384387 -62.56194948421307,0.0,56.81334188723669 -62.93105616448062,0.0,56.66212685006391 -63.26286333553133,0.0,56.44932866378102 -63.54049718634593,0.0,56.1689190806801 -63.75127471271653,0.0,55.83328730217937 -63.88416418871931,0.0,55.46207968931748 -63.92823476629064,0.0,55.07491905435815 -63.88394365762451,0.0,54.6866120873119 -63.77368256539719,0.0,54.30268901111988 -63.622337691735694,0.0,53.92762457035579 -63.45032669961374,0.0,53.56469634079292 -63.262873598342004,0.0,53.213111062854736 -63.061976215067894,0.0,52.87121085505328 -62.84963245649551,0.0,52.53733815412728 -62.62784022932895,0.0,52.20983515814548 -62.39859728115898,0.0,51.88704414473327 -62.16389539282593,0.0,51.56731351737983 -61.92498607033715,0.0,51.249727101450276 -61.681688401820495,0.0,50.934791991172034 -61.43365727043279,0.0,50.623178212836706 -61.180547877557586,0.0,50.31555579273595 -60.92201526546503,0.0,50.012594836718065 -60.65771431731198,0.0,49.71496521196134 -60.38730023448195,0.0,49.423337024314094 -60.11042805924512,0.0,49.13838030006798 -59.82675267475834,0.0,48.86076506551461 -59.53592936196179,0.0,48.59116126738897 -59.23761292445565,0.0,48.33023909109603 -58.93145864318008,0.0,48.078668403814106 -58.6171213217353,0.0,47.83711931139146 -58.294312726298585,0.0,47.6062044002026 -57.963459280631895,0.0,47.38581109755661 -57.625477398040104,0.0,47.17532928333587 -57.281293197742,0.0,46.97413937017879 -56.931832719399765,0.0,46.78162177072379 -56.578022082232195,0.0,46.597156579382585 -56.220787405458154,0.0,46.420124367906965 -55.860931575011534,0.0,46.25007031080305 -55.49845689803577,0.0,46.087613756762394 -55.13304482961621,0.0,45.933804137845456 -54.76437602927139,0.0,45.7896919203494 -54.39213115651987,0.0,45.65632765012808 -54.0159909504369,0.0,45.53476171392197 -53.635636070541054,0.0,45.42604465758495 -53.25094590891756,0.0,45.33067880194406 -52.86251332188619,0.0,45.24719926999762 -52.47109091556416,0.0,45.173700520337775 -52.07743137562531,0.0,45.10827677288657 -51.682287387743486,0.0,45.049022327122785 -51.28641171714922,0.0,44.99403148252517 -50.89055506059957,0.0,44.94140880138315 -50.49520533916393,0.0,44.890752522503135 -50.100314182385745,0.0,44.84470631409587 -49.7057676651107,0.0,44.806284737577045 -49.311452100854474,0.0,44.77850251347566 -48.917253723576124,0.0,44.7643741236507 -48.523058608121325,0.0,44.7669142886312 -48.12876181923969,0.0,44.788436357325736 -47.734316577608105,0.0,44.82653063769594 -47.339700209575035,0.0,44.876837503672505 -46.94489012104562,0.0,44.93499112376574 -46.54986379748169,0.0,44.996625825599295 -46.15459864478841,0.0,45.05737593679682 -45.75907206887091,0.0,45.11287570542524 -45.36330276554711,0.0,45.16005503951189 -44.96746257722856,0.0,45.200650422536626 -44.57175851037581,0.0,45.237512370057445 -44.17639788967611,0.0,45.27349147718901 -43.78158780114671,0.0,45.31143833904599 -43.38753556947483,0.0,45.35420355074302 -42.994447485110996,0.0,45.404629513057586 -42.602404616303986,0.0,45.46421236876341 -42.211224062264854,0.0,45.53161636133753 -41.82068950840242,0.0,45.605147490562885 -41.43058471968215,0.0,45.683112154005826 -41.04069330195621,0.0,45.76381635144931 -40.65079909974674,0.0,45.845566400902996 -40.26069073097625,0.0,45.92669455585161 -39.87033199735895,0.0,46.00645250623823 -39.47990404943699,0.0,46.08523350069264 -39.089601562386804,0.0,46.163501752395945 -38.699619131828086,0.0,46.24172155408603 -38.310151592050595,0.0,46.32035727805733 -37.92139353867406,0.0,46.39987321704773 -37.53341243575633,0.0,46.4804512376094 -37.14578679204914,0.0,46.56118845107177 -36.757977611099626,0.0,46.6409214206634 -36.36944597601162,0.0,46.71848655049952 -35.97965304944562,0.0,46.7927204833654 -35.58805983494879,0.0,46.86245962337625 -35.19412980232512,0.0,46.92653751060712 -34.79777456411199,0.0,46.9832049325106 -34.399879506512185,0.0,47.02944708900101 -34.0014577837437,0.0,47.0620828269915 -33.603522470467865,0.0,47.07793123206524 -33.20708672090267,0.0,47.073811230692016 -32.813163609709456,0.0,47.04654190845507 -32.42276899603307,0.0,46.99299111917745 -32.03701818485839,0.0,46.91186017974532 -31.657153692288773,0.0,46.80419088477862 -31.28442614920821,0.0,46.67117714125415 -30.92008634561393,0.0,46.514013333488734 -30.56538499194661,0.0,46.3338933684592 -30.221572798646797,0.0,46.13201155092568 -29.889931662370586,0.0,45.90954380805712 -29.572201964874765,0.0,45.667401143304645 -29.270472943922897,0.0,45.40629232705919 -28.986842588512467,0.0,45.126921356311314 -28.72340880808428,0.0,44.82999206893827 -28.48226959163584,0.0,44.51620830281729 -28.26551966634105,0.0,44.18627572562909 -28.07460163333341,0.0,43.841228733223076 -27.909511355665984,0.0,43.48283173347103 -27.770050100772103,0.0,43.11294722762126 -27.656019454311775,0.0,42.733437716922154 -27.56722068371832,0.0,42.34616554350869 -27.503455295095094,0.0,41.952993288185866 -27.464524635432085,0.0,41.55578337264538 -27.45023021083265,0.0,41.1563982185789 -27.46037344784346,0.0,40.756700327234746 -27.494755693454515,0.0,40.35855212030462 -27.553178374212465,0.0,39.963816099036855 -27.63544291666401,0.0,39.57435476467977 -27.741350826912495,0.0,39.1920304593684 -27.87057011496561,0.0,38.81857895057257 -28.020743596188495,0.0,38.4538100182895 -28.187939102510555,0.0,38.096035629052565 -28.36818293727842,0.0,37.743528368842505 -28.55750140383868,0.0,37.39456090319669 -28.751921044208018,0.0,37.047405818095854 -28.94746808217635,0.0,36.700335779077385 -29.140579810857886,0.0,36.351815183258225 -29.330803234562232,0.0,36.00175954145271 -29.519107990007797,0.0,35.65074850357307 -29.70647119224016,0.0,35.29936498135508 -29.893869876748248,0.0,34.94819196609123 -30.082280999464295,0.0,34.59781244907397 -30.272681595877195,0.0,34.248809421595766 -30.465824431217484,0.0,33.90162410495958 -30.661533764796708,0.0,33.5561109104556 -30.85939351522027,0.0,33.21197245524391 -31.05898783976359,0.0,32.868911356484524 -31.259900736588733,0.0,32.5266302313375 -31.461716124301134,0.0,32.184831776519516 -31.664018160176184,0.0,31.843218529633983 -31.866390762819314,0.0,31.50149318739759 -32.068418009949255,0.0,31.159358287413703 -32.26968397928478,0.0,30.816516526399038 -32.46977258943126,0.0,30.472670521513642 -32.66826791810748,0.0,30.127522810360876 -32.86475396347551,0.0,29.780776169214118 -33.05884360276934,0.0,29.43215501376154 -33.25141251627779,0.0,29.082343929165766 -33.44506308229882,0.0,28.733340663017554 -33.642522423992176,0.0,28.38723755579065 -33.84651782363089,0.0,28.04612686840219 -34.05977616570466,0.0,27.712100941325904 -34.28502473248654,0.0,27.38725219459225 -34.524904646373805,0.0,27.073657693793983 -34.780656752779734,0.0,26.77314636726385 -35.0523811339977,0.0,26.487344910274363 -35.340144935858895,0.0,26.21787413090431 -35.64401514508115,0.0,25.966354916789165 -35.96405890749562,0.0,25.7344080760077 -36.300340823119996,0.0,25.52365425752536 -36.65223764498575,0.0,25.33563566742901 -37.017483599074176,0.0,25.171708190079634 -37.393573048000405,0.0,25.033200103673053 -37.778000513492934,0.0,24.921439845518442 -38.16826035816693,0.0,24.837755932481624 -38.561846944637566,0.0,24.783476642758433 -38.95627181976111,0.0,24.759894931382313 -39.349814331835454,0.0,24.766701482012497 -39.741817899646485,0.0,24.80136790405595 -40.131703987075404,0.0,24.86120271574203 -40.5188939784467,0.0,24.943514594413415 -40.90280925808485,0.0,25.045611978742798 -41.282871369427724,0.0,25.164803546072864 -41.658390476572336,0.0,25.298653668890132 -42.02683596133883,0.0,25.448962635125447 -42.38416332163576,0.0,25.621013803366747 -42.72628318540863,0.0,25.820193717205576 -43.04971025441353,0.0,26.050212263370955 -43.35357624713217,0.0,26.307515724881004 -43.637721493323816,0.0,26.586583902935224 -43.90235681816931,0.0,26.88206875937131 -44.150680718109996,0.0,27.19001219064363 -44.387333733824,0.0,27.50712675595149 -44.61696595279011,0.0,27.830129469667906 -44.84422714426041,0.0,28.15573726660917 -45.073767316157,0.0,28.48066724070494 -45.31023639684532,0.0,28.801636247214844 -45.557673319449805,0.0,29.11535859558503 -45.81744168532863,0.0,29.41853690043084 -46.09017357224089,0.0,29.707870355430725 -46.37646374586653,0.0,29.980142166108774 -46.67516078249155,0.0,30.23610509769551 -46.98264747890987,0.0,30.482116046510953 -47.295123572013075,0.0,30.724948228939702 -47.609992093356865,0.0,30.968908604534178 -47.92760508121485,0.0,31.212257109764238 -48.24875834097712,0.0,31.452344348338755 -48.57424783714711,0.0,31.68652052618318 -48.90486937511489,0.0,31.91213608789302 -49.24141876027055,0.0,32.126541478063785 -49.58468145563679,0.0,32.32711315632268 -49.93493304552547,0.0,32.51250462599606 -50.29171830665935,0.0,32.68320054632973 -50.654525371410735,0.0,32.83982671010571 -51.02284269037863,0.0,32.98300898966269 -51.39615839593535,0.0,33.11337317778265 -51.77396093867989,0.0,33.23154514680428 -52.155738450984565,0.0,33.338150689509575 -52.540979383448374,0.0,33.433815678237224 -52.9291718684436,0.0,33.51916590576921 -53.31980419745595,0.0,33.594827324000896 -53.71236482108438,0.0,33.66142572571427 -54.106341871701204,0.0,33.71958690369135 -54.50122395901878,0.0,33.769936889384134 -54.89661242455367,0.0,33.81319614801434 -55.29239342270826,0.0,33.85032270102626 -55.68849718228117,0.0,33.882311643273326 -56.0848540911844,0.0,33.91015814916571 -56.48139437821661,0.0,33.93485731355683 -56.87804835173311,0.0,33.95740415174349 -57.274747036099285,0.0,33.97878683714869 -57.671455108152756,0.0,33.99962280910385 -58.06818696765116,0.0,34.01998486196388 -58.46496099218572,0.0,34.03990203391403 -58.861795718461025,0.0,34.059403442696286 -59.25870936495495,0.0,34.07851820605259 -59.65572038881544,0.0,34.09727528261155 -60.05284613339693,0.0,34.11568811745076 -60.450084768896005,0.0,34.133479932908266 -60.84741728126806,0.0,34.150118813075046 -61.24482433824177,0.0,34.1650640112515 -61.64228644843253,0.0,34.17777478073796 -62.03978420001233,0.0,34.18771037483484 -62.43729810159655,0.0,34.19433004684248 -62.83481017337732,0.0,34.197182551317276 -63.23231524417094,0.0,34.19660870904208 -63.629814666440865,0.0,34.1933628763809 -64.02731003132051,0.0,34.18820330797459 -64.42480285038665,0.0,34.181887940237374 -64.82229463521605,0.0,34.175174948253456 -65.2197868973855,0.0,34.16882234799375 -65.61728090980172,0.0,34.163477173871655 -66.01477667246472,0.0,34.15925541951496 -66.41227386714782,0.0,34.1561149198875 -66.80977201651099,0.0,34.15401327128312 -67.20727096144088,0.0,34.152908069995604 -67.60477014504077,0.0,34.1527571509888 -68.00226940819735,0.0,34.15351811055655 -68.39976827357057,0.0,34.15514854499264 -68.79726642293373,0.0,34.15760620970427 -69.19476345850349,0.0,34.160848700985234 -69.59225914160982,0.0,34.16483385379938 -69.9897529949127,0.0,34.16951910532718 -70.38724470018543,0.0,34.17486229053249 -70.78473393920133,0.0,34.18082108526577 -71.18222031417704,0.0,34.18735300626419 -71.57970358644253,0.0,34.19441588849158 -71.97718319910113,0.0,34.20196732824176 -72.37465899303946,0.0,34.2099650809219 -72.7721304909175,0.0,34.21836666326914 -73.16959745406525,0.0,34.22712983069064 -73.56705940514264,0.0,34.236212259036925 -73.96451602592302,0.0,34.245571624158444 -74.3619669981797,0.0,34.255165522349046 -74.75941200368595,0.0,34.264951709015904 -75.15685056510178,0.0,34.27488786000947 -75.55428244375717,0.0,34.2849315716236 -75.95170724186875,0.0,34.29504059926545 -76.34912487987984,0.0,34.30518025622601 -76.74653623291385,0.0,34.31533709742774 -77.14394217609416,0.0,34.32550133739994 -77.54134366410084,0.0,34.33566319067201 -77.93874157205727,0.0,34.34581287177324 -78.33613701375688,0.0,34.355940436119674 -78.73353078476637,0.0,34.36603625735397 -79.13092383976583,0.0,34.376090470448794 -79.52831713343528,0.0,34.38609321037684 -79.92571162045482,0.0,34.39603477122412 -80.32310825550451,0.0,34.40590528796328 -80.72050791370772,0.0,34.41569497512369 -81.11791162930122,0.0,34.42539396767802 -81.51532019785172,0.0,34.43499255971227 -81.9127347331526,0.0,34.44448096575579 -82.3101560307706,0.0,34.45384924122458 -82.7075850453858,0.0,34.463087759761336 -83.10502281123492,0.0,34.47218657678204 -83.50247020344133,0.0,34.48113590681605 -83.89992817668514,0.0,34.48992604394938 -84.29739768564637,0.0,34.498547043597995 -84.69487960544845,0.0,34.50698927940465 -85.09237489077144,0.0,34.51524280678528 -85.48988449629536,0.0,34.523297840269265 -85.887409456257,0.0,34.531144594385935 -86.28495056622305,0.0,34.53877328366464 -86.68250886043023,0.0,34.54617412263471 -87.08008354331189,0.0,34.55340566500675 -87.47766570452069,0.0,34.560886697102205 -87.87524341055585,0.0,34.56915446512714 -88.2728047279166,0.0,34.57874621528761 -88.67033796177212,0.0,34.590199193789644 -89.06783109906495,0.0,34.60405056728268 -89.46527228585094,0.0,34.620836627292675 -89.86261482236368,0.0,34.640045665305315 -90.25970961939977,0.0,34.65809118698984 -90.65638897149465,0.0,34.67082598259127 -91.05248533229707,0.0,34.67410268324119 -91.44783083722908,0.0,34.66377415874129 -91.84225793993944,0.0,34.635693199336515 -92.23558755835948,0.0,34.585730177296355 -92.62676580525513,0.0,34.511119304918516 -93.01325800505626,0.0,34.41140337000897 -93.39238620062643,0.0,34.28634847595204 -93.76147235527262,0.0,34.13572072613199 -94.11783851185835,0.0,33.95928614437648 -94.45880671324726,0.0,33.756810834069796 -94.78173209787849,0.0,33.52811054195956 -95.08473760563268,0.0,33.27415593900095 -95.36671922857246,0.0,32.99708041691049 -95.62660708857264,0.0,32.69906836323143 -95.86333106883808,0.0,32.38230408595041 -96.07582113213027,0.0,32.04897221128071 -96.26300835500417,0.0,31.701256967652284 -96.42508733307949,0.0,31.341358017489416 -96.56600344083435,0.0,30.97151989317944 -96.69039491180344,0.0,30.593995480560235 -96.80289997952137,0.0,30.211037585913 -96.90815671840947,0.0,29.824899174632293 -97.01080336200238,0.0,29.43783313255599 -97.11545316303975,0.0,29.0520797755678 -97.22474175450846,0.0,28.668894826178654 -97.33792337216515,0.0,28.28785003082316 -97.45392105734084,0.0,27.908352055841487 -97.57165769225324,0.0,27.52980780624383 -97.69005631823343,0.0,27.151623948370364 -97.80803989705574,0.0,26.773207307674603 -97.92455867843307,0.0,26.393979825377755 -98.03920915092502,0.0,26.013726141568696 -98.1522466914487,0.0,25.632600516634437 -98.26395627200324,0.0,25.250773679193124 -98.37462294414445,0.0,24.86841635786287 -98.48453167987145,0.0,24.485699440375143 -98.59396753074006,0.0,24.102793814461414 -98.7032153891927,0.0,23.71987004962648 -98.81256038634189,0.0,23.33709919271513 -98.92228749418669,0.0,22.954651892788835 -99.03268168472627,0.0,22.57269895802239 -99.14402792995978,0.0,22.191411196590586 -99.25661128144296,0.0,21.810959496224903 -99.37071671117498,0.0,21.431514585543464 -99.48640046572294,0.0,21.052978848509706 -99.60242106322018,0.0,20.673733306848312 -99.7170803665027,0.0,20.291623008984637 -99.82856265364533,0.0,19.90452673537297 -99.92456074615865,0.0,19.51339216509026 -99.9741168358215,0.0,19.124622098656253 -99.94435890132749,0.0,18.745180847581715 -99.81512799800026,0.0,18.38165260159859 -99.6056898082029,0.0,18.03944188410629 -99.34292971367327,0.0,17.723725447752262 -99.05325511966383,0.0,17.439388788207758 -98.75137048586151,0.0,17.18418474771529 -98.43986673440357,0.0,16.94848330935515 -98.12076953727264,0.0,16.722354288884176 -97.79564632002055,0.0,16.499431879635093 -97.4652580422151,0.0,16.27962562567183 -97.13028340182514,0.0,16.063483354237825 -96.79140117637624,0.0,15.851552813019847 -96.44929014339395,0.0,15.64438174970465 -96.10462915996052,0.0,15.442517911979003 -95.758084513204,0.0,15.24647778175758 -95.41001349213835,0.0,15.055993491725724 -95.06044974923584,0.0,14.869975911043671 -94.70941142341769,0.0,14.687297005659044 -94.3569167331618,0.0,14.506828821076127 -94.00298389694605,0.0,14.327443402799226 -93.64763113324832,0.0,14.148013432785994 -93.29058611958035,0.0,13.968932875676217 -92.93065805167552,0.0,13.795409590776108 -92.5664747360551,0.0,13.633601344055638 -92.19671887334398,0.0,13.489446881966742 -91.82148306750838,0.0,13.363248997203083 -91.44235877021512,0.0,13.249318512592808 -91.06100489718888,0.0,13.14169631517594 -90.67858456697441,0.0,13.036295658268175 -90.29536413530954,0.0,12.932417556949279 -89.91151576283254,0.0,12.829719360632906 -89.52721137151161,0.0,12.72785865740274 -89.14262304242827,0.0,12.626492876229133 -88.7579228566641,0.0,12.525279525639089 -88.37327963347708,0.0,12.423882558250053 -87.9887769869295,0.0,12.322138007761023 -87.60440704091081,0.0,12.220066956690076 -87.22015722546686,0.0,12.11769947745923 -86.83601528887016,0.0,12.01506588116053 -86.45196858160986,0.0,11.912196240215982 -86.0680046928451,0.0,11.809120786160953 -85.68411129129174,0.0,11.705869670974133 -85.30027572743894,0.0,11.602473126190887 -84.91648567000252,0.0,11.498961303789903 -84.53272870814165,0.0,11.395364355749876 -84.14899219234549,0.0,11.291712593162828 -83.76526387088654,0.0,11.188036008894123 -83.38153109425397,0.0,11.084364914035778 -82.99778304274037,0.0,10.9807260396296 -82.61401717053224,0.0,10.877125431982662 -82.23023443230964,0.0,10.77356134084817 -81.84643562363931,0.0,10.670032015979345 -81.46262177875796,0.0,10.566535786686075 -81.07879353411897,0.0,10.463070823164905 -80.6949519239591,0.0,10.35963553428239 -80.31109774384502,0.0,10.256228010678408 -79.9272318689002,0.0,10.152846661219513 -79.54335525380463,0.0,10.049489656102256 -79.1594686145684,0.0,9.94615532463652 -78.77557298542823,0.0,9.84284191657552 -78.39166908239416,0.0,9.739547681672471 -78.00775786014627,0.0,9.636270869680594 -77.62384011425128,0.0,9.53300980990978 -77.23991679938925,0.0,9.429762752113234 -76.85598879068357,0.0,9.3265278664875 -76.47205688370096,0.0,9.223303561899153 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv b/gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv deleted file mode 100644 index b5e9f738..00000000 --- a/gym/f110_gym/maps/Spielberg/Spielberg_centerline.csv +++ /dev/null @@ -1,865 +0,0 @@ -# x_m, y_m, w_tr_right_m, w_tr_left_m -0.0, 0.0, 1.1, 1.1 --0.383936998609612, -0.10320847281061823, 1.1, 1.1 --0.7678753496826622, -0.20641169488089267, 1.1, 1.1 --1.151814018982386, -0.3096112573442502, 1.1, 1.1 --1.5357522109420796, -0.41280906956082436, 1.1, 1.1 --1.9196891299950265, -0.5160067226640551, 1.1, 1.1 --2.3036237419044885, -0.6192059669007194, 1.1, 1.1 --2.6875553306604, -0.7224086320742855, 1.1, 1.1 --3.0714830211393926, -0.8256163093181935, 1.1, 1.1 --3.455406017774737, -0.9288305102091988, 1.1, 1.1 --3.8393244796797763, -1.0320512347473079, 1.1, 1.1 --4.223238645524531, -1.1352782442625122, 1.1, 1.1 --4.607148594865655, -1.2385113796414555, 1.1, 1.1 --4.991054566373195, -1.3417504817708008, 1.1, 1.1 --5.374956798717146, -1.4449953119805332, 1.1, 1.1 --5.75885553056753, -1.5482455520439593, 1.1, 1.1 --6.142750921037678, -1.651501201961079, 1.1, 1.1 --6.5266431292409575, -1.754761863948541, 1.1, 1.1 --6.910532393847366, -1.8580274584496597, 1.1, 1.1 --7.294418953526939, -1.961297746794434, 1.1, 1.1 --7.67830296739299, -2.0645725698695068, 1.1, 1.1 --8.062184674115569, -2.1678516890048765, 1.1, 1.1 --8.446064232807995, -2.2711347859738362, 1.1, 1.1 --8.82994180258362, -2.3744218607764065, 1.1, 1.1 --9.213817781225814, -2.4777125951858805, 1.1, 1.1 --9.597692168734559, -2.5810067505322563, 1.1, 1.1 --9.98156520377988, -2.6843042472588556, 1.1, 1.1 --10.365437204588462, -2.787604767138985, 1.1, 1.1 --10.749308250716984, -2.8909081510593153, 1.1, 1.1 --11.133178580835468, -2.9942142399064884, 1.1, 1.1 --11.517048433613908, -3.097522715453825, 1.1, 1.1 --11.900917968165663, -3.200833498144647, 1.1, 1.1 --12.284787423160738, -3.3041462697522674, 1.1, 1.1 --12.66865703726917, -3.4074609507200213, 1.1, 1.1 --13.052526890047611, -3.5107772228212153, 1.1, 1.1 --13.436397220166082, -3.6140949269425, 1.1, 1.1 --13.820268345851282, -3.717413903970537, 1.1, 1.1 --14.204140346659866, -3.8207338356786416, 1.1, 1.1 --14.588013461261864, -3.9240546425101406, 1.1, 1.1 --14.971887928327275, -4.027376085795013, 1.1, 1.1 --15.35576382741279, -4.130697926863244, 1.1, 1.1 --15.739641556301772, -4.23402000660149, 1.1, 1.1 --16.123521194550875, -4.337342086339743, 1.1, 1.1 --16.507402980830108, -4.440663927407974, 1.1, 1.1 --16.89128707425285, -4.543985370692847, 1.1, 1.1 --17.275173713489085, -4.647306257081011, 1.1, 1.1 --17.659063057652162, -4.750626347902459, 1.1, 1.1 --18.042955424968785, -4.853945404487168, 1.1, 1.1 --18.42685089499561, -4.957263267721802, 1.1, 1.1 --18.81074970640267, -5.060579619379668, 1.1, 1.1 --19.19465209785997, -5.163894459460765, 1.1, 1.1 --19.578558228480837, -5.2672074697384, 1.1, 1.1 --19.962468336935316, -5.370518411542572, 1.1, 1.1 --20.346382582336737, -5.473827125759918, 1.1, 1.1 --20.73030120335512, -5.577133373720441, 1.1, 1.1 --21.114224359103808, -5.6804370758674505, 1.1, 1.1 --21.498152288252808, -5.783737834417602, 1.1, 1.1 --21.882085229472157, -5.887035649370888, 1.1, 1.1 --22.266023341875172, -5.99033012294395, 1.1, 1.1 --22.6499668641319, -6.093621175580118, 1.1, 1.1 --23.033915955355663, -6.196908568609368, 1.1, 1.1 --23.417870774659807, -6.300192142918365, 1.1, 1.1 --23.80183164027103, -6.403471580280422, 1.1, 1.1 --24.185797517952583, -6.506746562468837, 1.1, 1.1 --24.569763156964118, -6.61001565746353, 1.1, 1.1 --24.953722113215207, -6.713277353687727, 1.1, 1.1 --25.337668022172096, -6.816529980451313, 1.1, 1.1 --25.72159451930101, -6.919772105734195, 1.1, 1.1 --26.105495160511513, -7.0230020588462585, 1.1, 1.1 --26.4893637403832, -7.126218248654065, 1.1, 1.1 --26.873193735268973, -7.22941924313752, 1.1, 1.1 --27.256978780635052, -7.332603371606509, 1.1, 1.1 --27.64071259150436, -7.435769042927594, 1.1, 1.1 --28.0243886442298, -7.538914665967332, 1.1, 1.1 --28.408000733390935, -7.642038808705627, 1.1, 1.1 --28.79154241489736, -7.745139800452367, 1.1, 1.1 --29.17500939268876, -7.848217322980869, 1.1, 1.1 --29.55847652959351, -7.951318473840951, 1.1, 1.1 --29.94211956630006, -8.054550734096505, 1.1, 1.1 --30.326120767143983, -8.158025323974991, 1.1, 1.1 --30.710662476017525, -8.26185370237389, 1.1, 1.1 --31.095926877699572, -8.366147169077333, 1.1, 1.1 --31.48209623652569, -8.471017103426139, 1.1, 1.1 --31.869050581034482, -8.576336851198471, 1.1, 1.1 --32.25220171883802, -8.678462955486445, 1.1, 1.1 --32.62487206067143, -8.77238422107705, 1.1, 1.1 --32.99993594453883, -8.872591895776262, 1.1, 1.1 --33.396885789318524, -8.994200872141919, 1.1, 1.1 --33.801994329925826, -9.095399186520948, 1.1, 1.1 --34.19315706327043, -9.120088008544716, 1.1, 1.1 --34.55016524219926, -9.020283527059233, 1.1, 1.1 --34.866458066641975, -8.806431214872264, 1.1, 1.1 --35.14145349998617, -8.5145717559795, 1.1, 1.1 --35.374622808589685, -8.180804785870604, 1.1, 1.1 --35.570474548611806, -7.832287054091635, 1.1, 1.1 --35.74433809739808, -7.476964362815932, 1.1, 1.1 --35.912944541298174, -7.120294140629777, 1.1, 1.1 --36.08998295819422, -6.766799104780075, 1.1, 1.1 --36.277394451326494, -6.4173916907380635, 1.1, 1.1 --36.47428400813493, -6.072112790633152, 1.1, 1.1 --36.67975685472948, -5.731003296594757, 1.1, 1.1 --36.89291789899339, -5.394104180308963, 1.1, 1.1 --37.112872367036594, -5.061456254348504, 1.1, 1.1 --37.338724768959004, -4.733099058379374, 1.1, 1.1 --37.56950013774517, -4.408787000955076, 1.1, 1.1 --37.80404903859795, -4.087652277897383, 1.1, 1.1 --38.04119944262535, -3.7687452212125345, 1.1, 1.1 --38.27977892315199, -3.4511160037934525, 1.1, 1.1 --38.51861537172921, -3.133814878089733, 1.1, 1.1 --38.75653652079499, -2.815892096550947, 1.1, 1.1 --38.99238855993523, -2.4964124704976745, 1.1, 1.1 --39.22571507252263, -2.1749954803676945, 1.1, 1.1 --39.45695696163346, -1.8519738321633459, 1.1, 1.1 --39.68661416139457, -1.5277270907667706, 1.1, 1.1 --39.9151865263762, -1.202635059730125, 1.1, 1.1 --40.14317391114858, -0.8770773834922285, 1.1, 1.1 --40.37107624983858, -0.5514336269352162, 1.1, 1.1 --40.59930604379055, -0.22601740246014637, 1.1, 1.1 --40.82792646100209, 0.09912276036306099, 1.1, 1.1 --41.05691331624487, 0.4240044435589187, 1.1, 1.1 --41.286242424290634, 0.7486451495952746, 1.1, 1.1 --41.515889599911084, 1.0730624604966286, 1.1, 1.1 --41.74583065787791, 1.3972739582875062, 1.1, 1.1 --41.976041492519535, 1.721297224992421, 1.1, 1.1 --42.20649783905095, 2.0451497630792006, 1.1, 1.1 --42.4371755122439, 2.368849234129043, 1.1, 1.1 --42.668050406426744, 2.692413140609789, 1.1, 1.1 --42.89909825681454, 3.015859064545952, 1.1, 1.1 --43.13029495773565, 3.339204587962038, 1.1, 1.1 --43.36161624440513, 3.6624672133258946, 1.1, 1.1 --43.59303801115135, 3.9856646022187006, 1.1, 1.1 --43.82453599318935, 4.308814336664981, 1.1, 1.1 --44.056086005290844, 4.6319338395758995, 1.1, 1.1 --44.28766402134088, 4.955040772532635, 1.1, 1.1 --44.519245696997835, 5.278152717559711, 1.1, 1.1 --44.75080692659007, 5.601287256681635, 1.1, 1.1 --44.982323524889345, 5.924461892366256, 1.1, 1.1 --45.21377122711063, 6.247694206638079, 1.1, 1.1 --45.44512600713902, 6.571001781521618, 1.1, 1.1 --45.676363520632876, 6.894402199041385, 1.1, 1.1 --45.90745966192057, 7.217912961665234, 1.1, 1.1 --46.13839024577383, 7.541551730974336, 1.1, 1.1 --46.36913108696434, 7.865336009436534, 1.1, 1.1 --46.59965807982051, 8.189283458633026, 1.1, 1.1 --46.82988578047659, 8.513449370450843, 1.1, 1.1 --47.0592528370549, 8.838184271586845, 1.1, 1.1 --47.28697450254276, 9.163976878677182, 1.1, 1.1 --47.512264836577444, 9.491316863038044, 1.1, 1.1 --47.73433766012617, 9.820693816428953, 1.1, 1.1 --47.95240703282619, 10.15259733060945, 1.1, 1.1 --48.16568685520139, 10.487516997339048, 1.1, 1.1 --48.373634152965366, 10.82578894355699, 1.1, 1.1 --48.576737324527514, 11.167098363512139, 1.1, 1.1 --48.77575828413569, 11.510957574805092, 1.1, 1.1 --48.971458946037664, 11.856879054149793, 1.1, 1.1 --49.164601383594594, 12.204375119146851, 1.1, 1.1 --49.355947431497626, 12.552958166953532, 1.1, 1.1 --49.546258447097856, 12.90214107206714, 1.1, 1.1 --49.73607430197151, 13.251576012717667, 1.1, 1.1 --49.92540732740276, 13.601247634467406, 1.1, 1.1 --50.11419268470392, 13.951189112448603, 1.1, 1.1 --50.302365535187306, 14.301433542236794, 1.1, 1.1 --50.48986104016521, 14.652014178520885, 1.1, 1.1 --50.676614440506654, 15.002964196433105, 1.1, 1.1 --50.86256089752392, 15.354316691548998, 1.1, 1.1 --51.047635572529366, 15.706104918557475, 1.1, 1.1 --51.23177362683526, 16.058361893477418, 1.1, 1.1 --51.41491030131063, 16.411120950554384, 1.1, 1.1 --51.596980677711066, 16.764415264920615, 1.1, 1.1 --51.77792007646227, 17.118277852594993, 1.1, 1.1 --51.957663579319885, 17.47274196826641, 1.1, 1.1 --52.13616496385746, 17.82783124026644, 1.1, 1.1 --52.31345963279404, 18.183527529673892, 1.1, 1.1 --52.489605582943504, 18.5398011618501, 1.1, 1.1 --52.66466065200644, 18.89662230304305, 1.1, 1.1 --52.83868275724002, 19.25396143772743, 1.1, 1.1 --53.011729815901504, 19.611788811707918, 1.1, 1.1 --53.18385974524809, 19.970074670789177, 1.1, 1.1 --53.355130382980335, 20.328789419889223, 1.1, 1.1 --53.52559972591214, 20.687903304812732, 1.1, 1.1 --53.69532561174403, 21.047386650921034, 1.1, 1.1 --53.86436595773325, 21.407209783575478, 1.1, 1.1 --54.03277868113701, 21.767343028137397, 1.1, 1.1 --54.200621619655855, 22.127756630411476, 1.1, 1.1 --54.36795284966036, 22.488420915759036, 1.1, 1.1 --54.53483004973773, 22.84930620954143, 1.1, 1.1 --54.70131129625851, 23.210382837120008, 1.1, 1.1 --54.86745442692327, 23.5716211238561, 1.1, 1.1 --55.03331743854589, 23.932991315554386, 1.1, 1.1 --55.19895808927025, 24.29446373757619, 1.1, 1.1 --55.364434296353586, 24.65600871528287, 1.1, 1.1 --55.52980405660976, 25.017596574035757, 1.1, 1.1 --55.69512528729603, 25.379197639196196, 1.1, 1.1 --55.86045582611291, 25.74078215656886, 1.1, 1.1 --56.02585351076098, 26.102320451515087, 1.1, 1.1 --56.19137641761077, 26.46378284939622, 1.1, 1.1 --56.35708230480617, 26.825139675573613, 1.1, 1.1 --56.52302916916109, 27.18636117585191, 1.1, 1.1 --56.689257345908224, 27.54742642682639, 1.1, 1.1 --56.85565625127349, 27.908390004374045, 1.1, 1.1 --57.02203773372758, 28.269344989801123, 1.1, 1.1 --57.188213164401176, 28.630384941753903, 1.1, 1.1 --57.3539937553116, 28.99160325976532, 1.1, 1.1 --57.51919087758952, 29.35309350248166, 1.1, 1.1 --57.68361574325229, 29.71494906943585, 1.1, 1.1 --57.847264294909614, 30.07717783673841, 1.1, 1.1 --58.010995585505825, 30.439387112656348, 1.1, 1.1 --58.17592094219218, 30.801067098035418, 1.1, 1.1 --58.34315169211994, 31.161707993721425, 1.1, 1.1 --58.513799082883686, 31.5208000801168, 1.1, 1.1 --58.68897444163469, 31.877833637623993, 1.1, 1.1 --58.8697893341942, 32.23229823063544, 1.1, 1.1 --59.057475138731554, 32.58340330450141, 1.1, 1.1 --59.253576368477084, 32.929624871612916, 1.1, 1.1 --59.459688134704514, 33.26932080270309, 1.1, 1.1 --59.677208884594386, 33.60101046854923, 1.1, 1.1 --59.9037899460757, 33.92629240136197, 1.1, 1.1 --60.133723525715354, 34.24952543164384, 1.1, 1.1 --60.36123500247579, 34.57512551158792, 1.1, 1.1 --60.58352445884239, 34.90518307230783, 1.1, 1.1 --60.802320024844484, 35.238248829909665, 1.1, 1.1 --61.01972963406355, 35.57257675411289, 1.1, 1.1 --61.237861140524394, 35.90642057596695, 1.1, 1.1 --61.45882263692187, 36.238034344748, 1.1, 1.1 --61.68472205683744, 36.565671711948816, 1.1, 1.1 --61.91730487365491, 36.88788474613889, 1.1, 1.1 --62.15656193835704, 37.20466915125794, 1.1, 1.1 --62.401953618037574, 37.51645692003494, 1.1, 1.1 --62.65294012067696, 37.823680204312254, 1.1, 1.1 --62.90898157469899, 38.12677107637551, 1.1, 1.1 --63.16953834719739, 38.42616160851044, 1.1, 1.1 --63.43407064615264, 38.72228411167266, 1.1, 1.1 --63.70203867954515, 39.0155705785912, 1.1, 1.1 --63.97290265535538, 39.30645316110839, 1.1, 1.1 --64.24612286112041, 39.59536393150991, 1.1, 1.1 --64.52115942526402, 39.88273512119474, 1.1, 1.1 --64.79747271488002, 40.16899880244859, 1.1, 1.1 --65.07452293794879, 40.45458712711376, 1.1, 1.1 --65.35177356427434, 40.739929542105784, 1.1, 1.1 --65.62889594524464, 41.025291528039105, 1.1, 1.1 --65.90588729637611, 41.31068104058093, 1.1, 1.1 --66.1827735531439, 41.59608360041699, 1.1, 1.1 --66.45958049190966, 41.88148456911959, 1.1, 1.1 --66.73633404814854, 42.16686930826111, 1.1, 1.1 --67.0130599982222, 42.45222333852723, 1.1, 1.1 --67.28978427760578, 42.7375320214903, 1.1, 1.1 --67.56653266266096, 43.02278079827936, 1.1, 1.1 --67.84333100930616, 43.30795503046675, 1.1, 1.1 --68.12020525301647, 43.59304023873814, 1.1, 1.1 --68.39718117015357, 43.87802178466594, 1.1, 1.1 --68.6742846961926, 44.16288502982246, 1.1, 1.1 --68.95154160749523, 44.44761557445006, 1.1, 1.1 --69.22897815776328, 44.732197586771036, 1.1, 1.1 --69.5066244989754, 45.016605131310286, 1.1, 1.1 --69.78451253335706, 45.30080646495571, 1.1, 1.1 --70.06267456091715, 45.58476968548181, 1.1, 1.1 --70.34114280210775, 45.868462890663125, 1.1, 1.1 --70.61994923871107, 46.15185433738752, 1.1, 1.1 --70.89912609117923, 46.43491212342953, 1.1, 1.1 --71.17870557996447, 46.717604505677, 1.1, 1.1 --71.4587197664055, 46.999899422791124, 1.1, 1.1 --71.73920087095456, 47.281765211216445, 1.1, 1.1 --72.02018103450709, 47.56316996872749, 1.1, 1.1 --72.30169239795866, 47.84408179309879, 1.1, 1.1 --72.58376710220466, 48.12446894121821, 1.1, 1.1 --72.86643720858396, 48.40429959041692, 1.1, 1.1 --73.14963573037875, 48.683618292431305, 1.1, 1.1 --73.43301158399541, 48.96268861851567, 1.1, 1.1 --73.71616316735371, 49.24181312269366, 1.1, 1.1 --73.99868879881666, 49.52129427943226, 1.1, 1.1 --74.28018695586066, 49.80143464275512, 1.1, 1.1 --74.56025595684872, 50.082536766685855, 1.1, 1.1 --74.83847423097588, 50.36492977717658, 1.1, 1.1 --75.11298516418756, 50.650866321395114, 1.1, 1.1 --75.37955132946264, 50.9457899055102, 1.1, 1.1 --75.63370371030787, 51.255443805230655, 1.1, 1.1 --75.86246239701535, 51.585213052571234, 1.1, 1.1 --76.02803271964164, 51.93943778221657, 1.1, 1.1 --76.08812195356482, 52.32226862485863, 1.1, 1.1 --76.00649139823248, 52.72013289402634, 1.1, 1.1 --75.77804505101929, 53.02828150195576, 1.1, 1.1 --75.4201704999323, 53.1514411174155, 1.1, 1.1 --75.0107297007509, 53.18263504983921, 1.1, 1.1 --74.6085742242518, 53.21589626238503, 1.1, 1.1 --74.2141051156186, 53.25718999387664, 1.1, 1.1 --73.82268533466674, 53.304887321454714, 1.1, 1.1 --73.43081208068446, 53.35731469096692, 1.1, 1.1 --73.03806330552675, 53.41267738344951, 1.1, 1.1 --72.64453511365336, 53.46916023387394, 1.1, 1.1 --72.25032345041079, 53.52494815676838, 1.1, 1.1 --71.85552449981546, 53.57822606666105, 1.1, 1.1 --71.46023428677049, 53.62717879852339, 1.1, 1.1 --71.0645485179523, 53.67000526885789, 1.1, 1.1 --70.66853855569569, 53.70579264440989, 1.1, 1.1 --70.27223709779285, 53.73502900536222, 1.1, 1.1 --69.87567381888243, 53.758325665182554, 1.1, 1.1 --69.47887815493308, 53.77629401689524, 1.1, 1.1 --69.08187962147011, 53.789545612638015, 1.1, 1.1 --68.6847075749055, 53.79869160676523, 1.1, 1.1 --68.28739168987791, 53.804343630971246, 1.1, 1.1 --67.88996140235595, 53.80711307828047, 1.1, 1.1 --67.49244614830832, 53.8076111826039, 1.1, 1.1 --67.09487544326028, 53.806449496079246, 1.1, 1.1 --66.69727880273716, 53.80423941173091, 1.1, 1.1 --66.2996857422643, 53.801592322583254, 1.1, 1.1 --65.9021256978103, 53.799119621660616, 1.1, 1.1 --65.50462524130366, 53.79738584310758, 1.1, 1.1 --65.10718214515754, 53.79650300271833, 1.1, 1.1 --64.70977811133736, 53.79632933050334, 1.1, 1.1 --64.31239484180855, 53.79672043110291, 1.1, 1.1 --63.91501372030991, 53.797531988714056, 1.1, 1.1 --63.51761636925017, 53.79861944886371, 1.1, 1.1 --63.120184331481454, 53.79983841619221, 1.1, 1.1 --62.72271100379994, 53.800867163517914, 1.1, 1.1 --62.32525104163933, 53.80046866414782, 1.1, 1.1 --61.92787859181795, 53.79711073613577, 1.1, 1.1 --61.53066796026741, 53.78926135664895, 1.1, 1.1 --61.133693452919395, 53.77538842329779, 1.1, 1.1 --60.73702929614887, 53.75395983369285, 1.1, 1.1 --60.340749716330826, 53.72344491746471, 1.1, 1.1 --59.9448776257868, 53.683751229760475, 1.1, 1.1 --59.54928827965508, 53.638922238434944, 1.1, 1.1 --59.15383059981555, 53.59373969725898, 1.1, 1.1 --58.758355258394815, 53.5528190070024, 1.1, 1.1 --58.36275016004204, 53.51709941373493, 1.1, 1.1 --57.9669394872488, 53.48393008914528, 1.1, 1.1 --57.57085315058708, 53.450509206358774, 1.1, 1.1 --57.174710726471574, 53.41389969215823, 1.1, 1.1 --56.77921366607937, 53.37094012351148, 1.1, 1.1 --56.38510860877728, 53.31844926777498, 1.1, 1.1 --55.99283247980795, 53.254818886824154, 1.1, 1.1 --55.60191549702318, 53.183042777783236, 1.1, 1.1 --55.21172303685037, 53.10695183307941, 1.1, 1.1 --54.821698361698814, 53.02990716299155, 1.1, 1.1 --54.43170025847572, 52.95275644385991, 1.1, 1.1 --54.041726260924236, 52.87551017716518, 1.1, 1.1 --53.65177390278753, 52.79817822793472, 1.1, 1.1 --53.26184079736546, 52.72077054075248, 1.1, 1.1 --52.87192447840118, 52.643297060202514, 1.1, 1.1 --52.48202247963787, 52.56576765131212, 1.1, 1.1 --52.09213241437536, 52.48819225866531, 1.1, 1.1 --51.70225181635681, 52.410580826846086, 1.1, 1.1 --51.3123782193254, 52.33294314132509, 1.1, 1.1 --50.922509157024294, 52.25528930579967, 1.1, 1.1 --50.532642322310004, 52.17762910574049, 1.1, 1.1 --50.14277508981236, 52.09997248573156, 1.1, 1.1 --49.75290515238785, 52.02232946991356, 1.1, 1.1 --49.363030043779666, 51.94470976420044, 1.1, 1.1 --48.97314729773098, 51.867123472289556, 1.1, 1.1 --48.58325444798495, 51.78958045920824, 1.1, 1.1 --48.19334918739808, 51.71209058998384, 1.1, 1.1 --47.8034288906002, 51.634663888757, 1.1, 1.1 --47.41349125044783, 51.55731014099841, 1.1, 1.1 --47.02353372112745, 51.48003929129203, 1.1, 1.1 --46.633553915938904, 51.40286136377857, 1.1, 1.1 --46.24354944818206, 51.32578614392866, 1.1, 1.1 --45.85351785160004, 51.248823576326316, 1.1, 1.1 --45.463456580379365, 51.17198368511218, 1.1, 1.1 --45.07336332737655, 51.09527625575698, 1.1, 1.1 --44.68323562633474, 51.018711312401315, 1.1, 1.1 --44.293071329223814, 50.942297288052465, 1.1, 1.1 --43.90287298185727, 50.8660275795066, 1.1, 1.1 --43.51264551674878, 50.789886354986066, 1.1, 1.1 --43.12239418463869, 50.71385746448638, 1.1, 1.1 --42.73212399759732, 50.63792499667317, 1.1, 1.1 --42.34184012680837, 50.56207296065536, 1.1, 1.1 --41.95154766389885, 50.486285285985204, 1.1, 1.1 --41.56125178005242, 50.410545981771634, 1.1, 1.1 --41.17095748733944, 50.33483897756689, 1.1, 1.1 --40.780670036500254, 50.25914836203657, 1.1, 1.1 --40.390394360048525, 50.18345806473297, 1.1, 1.1 --40.00013578828128, 50.107752094764955, 1.1, 1.1 --39.60989933326885, 50.03201446124149, 1.1, 1.1 --39.21969008663824, 49.95622909371483, 1.1, 1.1 --38.829503752329174, 49.8804259850503, 1.1, 1.1 --38.43930659831271, 49.80478071682304, 1.1, 1.1 --38.049058925809526, 49.72949735189674, 1.1, 1.1 --37.65872087692694, 49.6547798735784, 1.1, 1.1 --37.26825299155565, 49.580832424288445, 1.1, 1.1 --36.877615332246286, 49.507859146447174, 1.1, 1.1 --36.48676843888955, 49.43606410291834, 1.1, 1.1 --36.095672453592755, 49.36565143612228, 1.1, 1.1 --35.704287836689936, 49.29682512936605, 1.1, 1.1 --35.31257473028839, 49.22978932506996, 1.1, 1.1 --34.92049351516548, 49.16474816565445, 1.1, 1.1 --34.52800457209852, 49.101905634426494, 1.1, 1.1 --34.135068122751534, 49.04146595336315, 1.1, 1.1 --33.74165496982588, 48.983610273006576, 1.1, 1.1 --33.347797811113765, 48.92838473622654, 1.1, 1.1 --32.95355193850222, 48.87578600164281, 1.1, 1.1 --32.55897272343497, 48.82581080743185, 1.1, 1.1 --32.16411545779906, 48.778455732656745, 1.1, 1.1 --31.76903559259488, 48.73371735638058, 1.1, 1.1 --31.373788419709463, 48.691592496336526, 1.1, 1.1 --30.978414910828903, 48.65206396828339, 1.1, 1.1 --30.58290862186276, 48.615070593140416, 1.1, 1.1 --30.187253641476644, 48.580541645026194, 1.1, 1.1 --29.79143397877947, 48.54840671628598, 1.1, 1.1 --29.395433642880164, 48.51859531970839, 1.1, 1.1 --28.99923664288767, 48.49103688852534, 1.1, 1.1 --28.602827147024243, 48.4656605377421, 1.1, 1.1 --28.206202291249692, 48.442350273730874, 1.1, 1.1 --27.80938363542213, 48.420905852348206, 1.1, 1.1 --27.41239560343987, 48.401117721320034, 1.1, 1.1 --27.0152623805312, 48.38277632837231, 1.1, 1.1 --26.618008311037748, 48.36567204167427, 1.1, 1.1 --26.220657580187815, 48.349595388508554, 1.1, 1.1 --25.823234532323024, 48.33433673704441, 1.1, 1.1 --25.425763432228337, 48.3196866941211, 1.1, 1.1 --25.028268624245396, 48.30543562790791, 1.1, 1.1 --24.63077429360249, 48.291373906574094, 1.1, 1.1 --24.233304784641234, 48.277292136958934, 1.1, 1.1 --23.83588428258996, 48.262980607675026, 1.1, 1.1 --23.438537211346922, 48.248229925561624, 1.1, 1.1 --23.041285846780326, 48.23284310829888, 1.1, 1.1 --22.644128756870057, 48.21677695661386, 1.1, 1.1 --22.247048916488293, 48.20009058111389, 1.1, 1.1 --21.850028823167214, 48.18284476309637, 1.1, 1.1 --21.453051133552318, 48.165100283858685, 1.1, 1.1 --21.056098424732433, 48.14691816336831, 1.1, 1.1 --20.659153273796377, 48.12835910336597, 1.1, 1.1 --20.262198337389673, 48.109484044262445, 1.1, 1.1 --19.86521611304447, 48.0903537673551, 1.1, 1.1 --19.468189257406284, 48.07102913349803, 1.1, 1.1 --19.07110034756391, 48.05157100354534, 1.1, 1.1 --18.673931960606208, 48.03204031790777, 1.1, 1.1 --18.276666753178674, 48.0124977783261, 1.1, 1.1 --17.879287222813478, 47.993004325211054, 1.1, 1.1 --17.4817967904475, 47.973691624854794, 1.1, 1.1 --17.084270955362463, 47.954937094109326, 1.1, 1.1 --16.686801128174533, 47.93717153235359, 1.1, 1.1 --16.28947832171647, 47.920825898079805, 1.1, 1.1 --15.892393867047751, 47.90633099066694, 1.1, 1.1 --15.495638936114469, 47.89411760949385, 1.1, 1.1 --15.099305337316125, 47.8845809125504, 1.1, 1.1 --14.703556400500373, 47.8734776651785, 1.1, 1.1 --14.308697305061001, 47.8473829972037, 1.1, 1.1 --13.915049937292967, 47.79179229529915, 1.1, 1.1 --13.526172469351751, 47.693253878691976, 1.1, 1.1 --13.157065789084204, 47.542038841519194, 1.1, 1.1 --12.825258618033496, 47.329240655236305, 1.1, 1.1 --12.547624767218892, 47.04883107213538, 1.1, 1.1 --12.336847240848291, 46.71319929363466, 1.1, 1.1 --12.203957764845512, 46.341991680772765, 1.1, 1.1 --12.159887187274183, 45.954831045813435, 1.1, 1.1 --12.204178295940308, 45.56652407876719, 1.1, 1.1 --12.314439388167633, 45.18260100257517, 1.1, 1.1 --12.465784261829132, 44.80753656181107, 1.1, 1.1 --12.637795253951083, 44.44460833224821, 1.1, 1.1 --12.825248355222817, 44.09302305431002, 1.1, 1.1 --13.026145738496929, 43.75112284650856, 1.1, 1.1 --13.238489497069306, 43.417250145582564, 1.1, 1.1 --13.460281724235868, 43.08974714960076, 1.1, 1.1 --13.689524672405845, 42.766956136188554, 1.1, 1.1 --13.924226560738893, 42.44722550883512, 1.1, 1.1 --14.163135883227676, 42.12963909290556, 1.1, 1.1 --14.406433551744325, 41.814703982627314, 1.1, 1.1 --14.654464683132032, 41.50309020429199, 1.1, 1.1 --14.907574076007238, 41.19546778419123, 1.1, 1.1 --15.166106688099795, 40.89250682817335, 1.1, 1.1 --15.430407636252843, 40.59487720341663, 1.1, 1.1 --15.700821719082876, 40.303249015769374, 1.1, 1.1 --15.977693894319703, 40.01829229152326, 1.1, 1.1 --16.26136927880648, 39.74067705696989, 1.1, 1.1 --16.552192591603035, 39.47107325884425, 1.1, 1.1 --16.850509029109173, 39.21015108255132, 1.1, 1.1 --17.15666331038474, 38.95858039526939, 1.1, 1.1 --17.471000631829522, 38.71703130284675, 1.1, 1.1 --17.79380922726624, 38.48611639165788, 1.1, 1.1 --18.124662672932928, 38.26572308901189, 1.1, 1.1 --18.46264455552472, 38.05524127479115, 1.1, 1.1 --18.80682875582282, 37.85405136163408, 1.1, 1.1 --19.15628923416506, 37.661533762179076, 1.1, 1.1 --19.51009987133263, 37.47706857083787, 1.1, 1.1 --19.867334548106665, 37.300036359362245, 1.1, 1.1 --20.227190378553292, 37.12998230225834, 1.1, 1.1 --20.58966505552905, 36.96752574821768, 1.1, 1.1 --20.95507712394861, 36.81371612930074, 1.1, 1.1 --21.323745924293434, 36.66960391180468, 1.1, 1.1 --21.69599079704495, 36.53623964158336, 1.1, 1.1 --22.072131003127918, 36.41467370537725, 1.1, 1.1 --22.452485883023765, 36.30595664904024, 1.1, 1.1 --22.837176044647265, 36.21059079339934, 1.1, 1.1 --23.225608631678632, 36.12711126145291, 1.1, 1.1 --23.617031038000658, 36.053612511793055, 1.1, 1.1 --24.010690577939517, 35.98818876434185, 1.1, 1.1 --24.40583456582134, 35.928934318578065, 1.1, 1.1 --24.801710236415605, 35.87394347398046, 1.1, 1.1 --25.197566892965256, 35.82132079283843, 1.1, 1.1 --25.59291661440089, 35.77066451395842, 1.1, 1.1 --25.987807771179074, 35.72461830555116, 1.1, 1.1 --26.38235428845412, 35.68619672903233, 1.1, 1.1 --26.77666985271035, 35.658414504930946, 1.1, 1.1 --27.170868229988702, 35.644286115105984, 1.1, 1.1 --27.565063345443498, 35.64682628008648, 1.1, 1.1 --27.95936013432513, 35.668348348781024, 1.1, 1.1 --28.353805375956718, 35.706442629151226, 1.1, 1.1 --28.748421743989788, 35.756749495127785, 1.1, 1.1 --29.143231832519202, 35.81490311522103, 1.1, 1.1 --29.538258156083128, 35.87653781705458, 1.1, 1.1 --29.933523308776415, 35.9372879282521, 1.1, 1.1 --30.32904988469392, 35.99278769688053, 1.1, 1.1 --30.72481918801771, 36.039967030967176, 1.1, 1.1 --31.120659376336267, 36.08056241399191, 1.1, 1.1 --31.516363443189015, 36.11742436151273, 1.1, 1.1 --31.91172406388871, 36.15340346864429, 1.1, 1.1 --32.30653415241811, 36.19135033050127, 1.1, 1.1 --32.700586384089995, 36.23411554219831, 1.1, 1.1 --33.09367446845383, 36.284541504512866, 1.1, 1.1 --33.48571733726084, 36.3441243602187, 1.1, 1.1 --33.87689789129997, 36.411528352792814, 1.1, 1.1 --34.267432445162406, 36.485059482018166, 1.1, 1.1 --34.65753723388267, 36.56302414546111, 1.1, 1.1 --35.04742865160861, 36.643728342904595, 1.1, 1.1 --35.43732285381808, 36.72547839235828, 1.1, 1.1 --35.82743122258857, 36.80660654730689, 1.1, 1.1 --36.21778995620587, 36.88636449769352, 1.1, 1.1 --36.608217904127834, 36.965145492147926, 1.1, 1.1 --36.99852039117802, 37.04341374385123, 1.1, 1.1 --37.388502821736736, 37.121633545541314, 1.1, 1.1 --37.77797036151423, 37.20026926951262, 1.1, 1.1 --38.16672841489076, 37.27978520850301, 1.1, 1.1 --38.55470951780849, 37.36036322906469, 1.1, 1.1 --38.942335161515686, 37.44110044252706, 1.1, 1.1 --39.330144342465196, 37.52083341211869, 1.1, 1.1 --39.718675977553204, 37.5983985419548, 1.1, 1.1 --40.1084689041192, 37.67263247482068, 1.1, 1.1 --40.500062118616036, 37.742371614831534, 1.1, 1.1 --40.8939921512397, 37.8064495020624, 1.1, 1.1 --41.29034738945283, 37.86311692396588, 1.1, 1.1 --41.68824244705264, 37.90935908045629, 1.1, 1.1 --42.08666416982112, 37.94199481844678, 1.1, 1.1 --42.48459948309696, 37.95784322352052, 1.1, 1.1 --42.88103523266215, 37.9537232221473, 1.1, 1.1 --43.27495834385537, 37.926453899910356, 1.1, 1.1 --43.66535295753175, 37.872903110632734, 1.1, 1.1 --44.05110376870643, 37.7917721712006, 1.1, 1.1 --44.43096826127605, 37.6841028762339, 1.1, 1.1 --44.803695804356614, 37.551089132709436, 1.1, 1.1 --45.16803560795089, 37.39392532494402, 1.1, 1.1 --45.522736961618214, 37.21380535991448, 1.1, 1.1 --45.866549154918026, 37.01192354238096, 1.1, 1.1 --46.19819029119424, 36.7894557995124, 1.1, 1.1 --46.51591998869006, 36.54731313475993, 1.1, 1.1 --46.817649009641926, 36.28620431851447, 1.1, 1.1 --47.101279365052356, 36.0068333477666, 1.1, 1.1 --47.36471314548054, 35.709904060393555, 1.1, 1.1 --47.60585236192898, 35.39612029427257, 1.1, 1.1 --47.82260228722377, 35.066187717084375, 1.1, 1.1 --48.013520320231414, 34.72114072467836, 1.1, 1.1 --48.17861059789884, 34.36274372492631, 1.1, 1.1 --48.31807185279272, 33.99285921907655, 1.1, 1.1 --48.43210249925305, 33.61334970837744, 1.1, 1.1 --48.520901269846505, 33.22607753496397, 1.1, 1.1 --48.58466665846973, 32.83290527964115, 1.1, 1.1 --48.62359731813274, 32.43569536410067, 1.1, 1.1 --48.63789174273217, 32.03631021003418, 1.1, 1.1 --48.627748505721364, 31.63661231869003, 1.1, 1.1 --48.59336626011031, 31.238464111759907, 1.1, 1.1 --48.53494357935236, 30.84372809049214, 1.1, 1.1 --48.45267903690081, 30.45426675613505, 1.1, 1.1 --48.34677112665233, 30.071942450823684, 1.1, 1.1 --48.21755183859921, 29.698490942027856, 1.1, 1.1 --48.06737835737633, 29.33372200974479, 1.1, 1.1 --47.90018285105427, 28.97594762050785, 1.1, 1.1 --47.7199390162864, 28.623440360297785, 1.1, 1.1 --47.530620549726144, 28.27447289465197, 1.1, 1.1 --47.336200909356805, 27.92731780955114, 1.1, 1.1 --47.14065387138847, 27.58024777053267, 1.1, 1.1 --46.947542142706936, 27.231727174713512, 1.1, 1.1 --46.75731871900259, 26.88167153290799, 1.1, 1.1 --46.569013963557026, 26.530660495028354, 1.1, 1.1 --46.381650761324664, 26.17927697281037, 1.1, 1.1 --46.194252076816575, 25.828103957546517, 1.1, 1.1 --46.00584095410053, 25.477724440529254, 1.1, 1.1 --45.81544035768763, 25.128721413051046, 1.1, 1.1 --45.62229752234734, 24.78153609641486, 1.1, 1.1 --45.426588188768115, 24.43602290191088, 1.1, 1.1 --45.228728438344554, 24.091884446699197, 1.1, 1.1 --45.029134113801234, 23.74882334793981, 1.1, 1.1 --44.82822121697609, 23.406542222792783, 1.1, 1.1 --44.62640582926369, 23.0647437679748, 1.1, 1.1 --44.42410379338864, 22.723130521089267, 1.1, 1.1 --44.22173119074551, 22.381405178852873, 1.1, 1.1 --44.01970394361557, 22.039270278868987, 1.1, 1.1 --43.818437974280045, 21.696428517854322, 1.1, 1.1 --43.618349364133564, 21.352582512968926, 1.1, 1.1 --43.41985403545734, 21.00743480181616, 1.1, 1.1 --43.223367990089315, 20.6606881606694, 1.1, 1.1 --43.02927835079548, 20.312067005216825, 1.1, 1.1 --42.836709437287034, 19.96225592062105, 1.1, 1.1 --42.643058871266, 19.613252654472838, 1.1, 1.1 --42.44559952957265, 19.267149547245936, 1.1, 1.1 --42.24160412993393, 18.926038859857474, 1.1, 1.1 --42.02834578786016, 18.592012932781188, 1.1, 1.1 --41.80309722107828, 18.267164186047534, 1.1, 1.1 --41.56321730719102, 17.953569685249267, 1.1, 1.1 --41.30746520078509, 17.653058358719132, 1.1, 1.1 --41.035740819567124, 17.367256901729647, 1.1, 1.1 --40.74797701770593, 17.097786122359594, 1.1, 1.1 --40.444106808483674, 16.84626690824445, 1.1, 1.1 --40.1240630460692, 16.614320067462984, 1.1, 1.1 --39.78778113044483, 16.403566248980646, 1.1, 1.1 --39.43588430857907, 16.215547658884294, 1.1, 1.1 --39.07063835449065, 16.05162018153492, 1.1, 1.1 --38.69454890556442, 15.913112095128335, 1.1, 1.1 --38.31012144007189, 15.801351836973724, 1.1, 1.1 --37.91986159539789, 15.717667923936908, 1.1, 1.1 --37.52627500892726, 15.663388634213717, 1.1, 1.1 --37.13185013380371, 15.639806922837595, 1.1, 1.1 --36.73830762172937, 15.64661347346778, 1.1, 1.1 --36.34630405391834, 15.681279895511235, 1.1, 1.1 --35.95641796648942, 15.741114707197314, 1.1, 1.1 --35.569227975118125, 15.823426585868697, 1.1, 1.1 --35.18531269547997, 15.925523970198082, 1.1, 1.1 --34.8052505841371, 16.04471553752815, 1.1, 1.1 --34.42973147699249, 16.178565660345416, 1.1, 1.1 --34.06128599222599, 16.32887462658073, 1.1, 1.1 --33.70395863192906, 16.50092579482203, 1.1, 1.1 --33.36183876815619, 16.70010570866086, 1.1, 1.1 --33.03841169915129, 16.93012425482624, 1.1, 1.1 --32.734545706432655, 17.187427716336288, 1.1, 1.1 --32.450400460241006, 17.46649589439051, 1.1, 1.1 --32.18576513539551, 17.761980750826595, 1.1, 1.1 --31.93744123545483, 18.069924182098912, 1.1, 1.1 --31.700788219740822, 18.387038747406773, 1.1, 1.1 --31.471156000774712, 18.71004146112319, 1.1, 1.1 --31.243894809304415, 19.035649258064453, 1.1, 1.1 --31.014354637407823, 19.360579232160223, 1.1, 1.1 --30.777885556719504, 19.68154823867013, 1.1, 1.1 --30.530448634115015, 19.995270587040313, 1.1, 1.1 --30.270680268236188, 20.298448891886125, 1.1, 1.1 --29.99794838132393, 20.58778234688601, 1.1, 1.1 --29.711658207698296, 20.860054157564058, 1.1, 1.1 --29.41296117107327, 21.116017089150795, 1.1, 1.1 --29.105474474654955, 21.362028037966237, 1.1, 1.1 --28.792998381551747, 21.604860220394986, 1.1, 1.1 --28.47812986020796, 21.848820595989462, 1.1, 1.1 --28.160516872349977, 22.092169101219522, 1.1, 1.1 --27.8393636125877, 22.33225633979404, 1.1, 1.1 --27.513874116417714, 22.566432517638464, 1.1, 1.1 --27.18325257844993, 22.792048079348305, 1.1, 1.1 --26.846703193294275, 23.006453469519066, 1.1, 1.1 --26.503440497928032, 23.20702514777797, 1.1, 1.1 --26.153188908039358, 23.39241661745134, 1.1, 1.1 --25.79640364690548, 23.563112537785013, 1.1, 1.1 --25.433596582154088, 23.719738701561, 1.1, 1.1 --25.06527926318619, 23.862920981117973, 1.1, 1.1 --24.69196355762947, 23.993285169237936, 1.1, 1.1 --24.314161014884935, 24.111457138259563, 1.1, 1.1 --23.932383502580258, 24.218062680964856, 1.1, 1.1 --23.547142570116446, 24.313727669692508, 1.1, 1.1 --23.158950085121223, 24.399077897224494, 1.1, 1.1 --22.768317756108875, 24.47473931545618, 1.1, 1.1 --22.375757132480445, 24.541337717169554, 1.1, 1.1 --21.981780081863615, 24.59949889514663, 1.1, 1.1 --21.586897994546042, 24.649848880839418, 1.1, 1.1 --21.19150952901115, 24.693108139469622, 1.1, 1.1 --20.79572853085656, 24.730234692481538, 1.1, 1.1 --20.399624771283655, 24.762223634728613, 1.1, 1.1 --20.003267862380426, 24.79007014062099, 1.1, 1.1 --19.60672757534821, 24.814769305012113, 1.1, 1.1 --19.210073601831713, 24.837316143198777, 1.1, 1.1 --18.813374917465538, 24.858698828603973, 1.1, 1.1 --18.416666845412067, 24.87953480055913, 1.1, 1.1 --18.019934985913665, 24.89989685341916, 1.1, 1.1 --17.623160961379103, 24.91981402536932, 1.1, 1.1 --17.226326235103794, 24.93931543415157, 1.1, 1.1 --16.829412588609866, 24.95843019750788, 1.1, 1.1 --16.432401564749387, 24.977187274066832, 1.1, 1.1 --16.03527582016789, 24.995600108906043, 1.1, 1.1 --15.638037184668814, 25.01339192436355, 1.1, 1.1 --15.240704672296767, 25.03003080453033, 1.1, 1.1 --14.84329761532305, 25.044976002706782, 1.1, 1.1 --14.445835505132294, 25.057686772193247, 1.1, 1.1 --14.048337753552497, 25.067622366290127, 1.1, 1.1 --13.650823851968276, 25.07424203829776, 1.1, 1.1 --13.253311780187499, 25.07709454277256, 1.1, 1.1 --12.85580670939388, 25.07652070049737, 1.1, 1.1 --12.458307287123958, 25.073274867836183, 1.1, 1.1 --12.06081192224431, 25.068115299429873, 1.1, 1.1 --11.66331910317817, 25.061799931692658, 1.1, 1.1 --11.265827318348768, 25.055086939708744, 1.1, 1.1 --10.868335056179323, 25.04873433944904, 1.1, 1.1 --10.470841043763102, 25.043389165326943, 1.1, 1.1 --10.073345281100103, 25.03916741097025, 1.1, 1.1 --9.675848086417, 25.036026911342784, 1.1, 1.1 --9.278349937053838, 25.0339252627384, 1.1, 1.1 --8.880850992123944, 25.03282006145089, 1.1, 1.1 --8.483351808524045, 25.03266914244408, 1.1, 1.1 --8.085852545367478, 25.03343010201183, 1.1, 1.1 --7.688353679994251, 25.035060536447922, 1.1, 1.1 --7.290855530631089, 25.037518201159553, 1.1, 1.1 --6.89335849506133, 25.040760692440518, 1.1, 1.1 --6.49586281195501, 25.044745845254667, 1.1, 1.1 --6.0983689586521175, 25.049431096782467, 1.1, 1.1 --5.700877253379394, 25.05477428198777, 1.1, 1.1 --5.3033880143634855, 25.060733076721053, 1.1, 1.1 --4.905901639387784, 25.06726499771947, 1.1, 1.1 --4.508418367122284, 25.07432787994686, 1.1, 1.1 --4.110938754463695, 25.08187931969704, 1.1, 1.1 --3.713462960525359, 25.08987707237718, 1.1, 1.1 --3.3159914626473204, 25.098278654724425, 1.1, 1.1 --2.9185244994995734, 25.10704182214593, 1.1, 1.1 --2.5210625484221754, 25.11612425049221, 1.1, 1.1 --2.1236059276417993, 25.12548361561373, 1.1, 1.1 --1.7261549553851319, 25.135077513804333, 1.1, 1.1 --1.328709949878873, 25.144863700471184, 1.1, 1.1 --0.9312713884630399, 25.15479985146476, 1.1, 1.1 --0.5338395098076538, 25.164843563078886, 1.1, 1.1 --0.1364147116960799, 25.17495259072073, 1.1, 1.1 -0.2610029263150168, 25.185092247681293, 1.1, 1.1 -0.6584142793490314, 25.19524908888302, 1.1, 1.1 -1.0558202225293325, 25.20541332885523, 1.1, 1.1 -1.4532217105360197, 25.215575182127292, 1.1, 1.1 -1.8506196184924484, 25.225724863228525, 1.1, 1.1 -2.248015060192062, 25.235852427574958, 1.1, 1.1 -2.6454088312015505, 25.24594824880925, 1.1, 1.1 -3.0428018862010004, 25.256002461904078, 1.1, 1.1 -3.4401951798704586, 25.26600520183213, 1.1, 1.1 -3.837589666889999, 25.275946762679403, 1.1, 1.1 -4.2349863019396805, 25.28581727941856, 1.1, 1.1 -4.6323859601429, 25.295606966578976, 1.1, 1.1 -5.029789675736394, 25.305305959133303, 1.1, 1.1 -5.427198244286894, 25.31490455116755, 1.1, 1.1 -5.824612779587775, 25.324392957211074, 1.1, 1.1 -6.222034077205782, 25.333761232679866, 1.1, 1.1 -6.6194630918209745, 25.342999751216617, 1.1, 1.1 -7.016900857670091, 25.352098568237327, 1.1, 1.1 -7.414348249876513, 25.361047898271334, 1.1, 1.1 -7.811806223120314, 25.369838035404662, 1.1, 1.1 -8.209275732081554, 25.378459035053282, 1.1, 1.1 -8.60675765188363, 25.38690127085993, 1.1, 1.1 -9.004252937206612, 25.39515479824057, 1.1, 1.1 -9.401762542730534, 25.403209831724553, 1.1, 1.1 -9.799287502692177, 25.41105658584122, 1.1, 1.1 -10.196828612658216, 25.41868527511992, 1.1, 1.1 -10.594386906865415, 25.42608611408999, 1.1, 1.1 -10.99196158974706, 25.433317656462037, 1.1, 1.1 -11.389543750955868, 25.440798688557486, 1.1, 1.1 -11.787121456991036, 25.44906645658243, 1.1, 1.1 -12.184682774351772, 25.45865820674289, 1.1, 1.1 -12.582216008207295, 25.470111185244924, 1.1, 1.1 -12.979709145500124, 25.48396255873796, 1.1, 1.1 -13.377150332286128, 25.500748618747963, 1.1, 1.1 -13.774492868798859, 25.5199576567606, 1.1, 1.1 -14.17158766583495, 25.538003178445127, 1.1, 1.1 -14.568267017929822, 25.550737974046548, 1.1, 1.1 -14.96436337873224, 25.554014674696475, 1.1, 1.1 -15.359708883664258, 25.543686150196574, 1.1, 1.1 -15.754135986374623, 25.515605190791796, 1.1, 1.1 -16.147465604794665, 25.465642168751636, 1.1, 1.1 -16.538643851690306, 25.3910312963738, 1.1, 1.1 -16.92513605149143, 25.291315361464253, 1.1, 1.1 -17.30426424706161, 25.166260467407326, 1.1, 1.1 -17.673350401707786, 25.01563271758728, 1.1, 1.1 -18.029716558293533, 24.83919813583176, 1.1, 1.1 -18.370684759682437, 24.636722825525077, 1.1, 1.1 -18.693610144313663, 24.40802253341485, 1.1, 1.1 -18.996615652067867, 24.154067930456236, 1.1, 1.1 -19.278597275007634, 23.876992408365776, 1.1, 1.1 -19.538485135007814, 23.57898035468672, 1.1, 1.1 -19.775209115273256, 23.262216077405693, 1.1, 1.1 -19.987699178565457, 22.928884202735993, 1.1, 1.1 -20.174886401439355, 22.58116895910757, 1.1, 1.1 -20.336965379514663, 22.2212700089447, 1.1, 1.1 -20.477881487269524, 21.851431884634724, 1.1, 1.1 -20.60227295823861, 21.47390747201552, 1.1, 1.1 -20.714778025956548, 21.090949577368285, 1.1, 1.1 -20.820034764844646, 20.704811166087577, 1.1, 1.1 -20.922681408437562, 20.317745124011275, 1.1, 1.1 -21.02733120947492, 19.931991767023085, 1.1, 1.1 -21.13661980094363, 19.54880681763394, 1.1, 1.1 -21.249801418600324, 19.167762022278445, 1.1, 1.1 -21.365799103776016, 18.78826404729677, 1.1, 1.1 -21.483535738688413, 18.409719797699115, 1.1, 1.1 -21.601934364668605, 18.03153593982565, 1.1, 1.1 -21.719917943490913, 17.653119299129887, 1.1, 1.1 -21.836436724868257, 17.27389181683304, 1.1, 1.1 -21.951087197360188, 16.89363813302398, 1.1, 1.1 -22.064124737883876, 16.51251250808972, 1.1, 1.1 -22.17583431843841, 16.130685670648408, 1.1, 1.1 -22.28650099057963, 15.748328349318152, 1.1, 1.1 -22.396409726306633, 15.365611431830425, 1.1, 1.1 -22.50584557717523, 14.982705805916698, 1.1, 1.1 -22.615093435627884, 14.599782041081763, 1.1, 1.1 -22.72443843277706, 14.217011184170415, 1.1, 1.1 -22.834165540621868, 13.834563884244119, 1.1, 1.1 -22.944559731161455, 13.452610949477673, 1.1, 1.1 -23.05590597639495, 13.071323188045872, 1.1, 1.1 -23.168489327878135, 12.690871487680187, 1.1, 1.1 -23.282594757610152, 12.311426576998748, 1.1, 1.1 -23.39827851215812, 11.93289083996499, 1.1, 1.1 -23.51429910965535, 11.553645298303595, 1.1, 1.1 -23.62895841293788, 11.17153500043992, 1.1, 1.1 -23.74044070008051, 10.784438726828254, 1.1, 1.1 -23.83643879259383, 10.393304156545542, 1.1, 1.1 -23.88599488225668, 10.004534090111537, 1.1, 1.1 -23.856236947762675, 9.625092839037, 1.1, 1.1 -23.727006044435438, 9.261564593053874, 1.1, 1.1 -23.51756785463807, 8.919353875561573, 1.1, 1.1 -23.254807760108452, 8.603637439207546, 1.1, 1.1 -22.965133166099005, 8.319300779663044, 1.1, 1.1 -22.663248532296688, 8.064096739170573, 1.1, 1.1 -22.35174478083874, 7.828395300810435, 1.1, 1.1 -22.03264758370781, 7.602266280339459, 1.1, 1.1 -21.70752436645573, 7.379343871090376, 1.1, 1.1 -21.377136088650275, 7.159537617127115, 1.1, 1.1 -21.042161448260316, 6.9433953456931095, 1.1, 1.1 -20.703279222811418, 6.73146480447513, 1.1, 1.1 -20.361168189829133, 6.524293741159933, 1.1, 1.1 -20.016507206395694, 6.322429903434288, 1.1, 1.1 -19.66996255963917, 6.126389773212864, 1.1, 1.1 -19.32189153857352, 5.935905483181008, 1.1, 1.1 -18.97232779567102, 5.749887902498954, 1.1, 1.1 -18.621289469852876, 5.567208997114328, 1.1, 1.1 -18.268794779596973, 5.38674081253141, 1.1, 1.1 -17.914861943381222, 5.207355394254509, 1.1, 1.1 -17.559509179683495, 5.027925424241279, 1.1, 1.1 -17.202464166015524, 4.8488448671315005, 1.1, 1.1 -16.842536098110703, 4.675321582231392, 1.1, 1.1 -16.478352782490273, 4.513513335510922, 1.1, 1.1 -16.10859691977916, 4.369358873422027, 1.1, 1.1 -15.73336111394356, 4.243160988658367, 1.1, 1.1 -15.3542368166503, 4.129230504048091, 1.1, 1.1 -14.97288294362406, 4.021608306631224, 1.1, 1.1 -14.59046261340958, 3.916207649723459, 1.1, 1.1 -14.207242181744725, 3.8123295484045623, 1.1, 1.1 -13.823393809267717, 3.7096313520881896, 1.1, 1.1 -13.43908941794679, 3.6077706488580237, 1.1, 1.1 -13.054501088863443, 3.5064048676844166, 1.1, 1.1 -12.669800903099274, 3.405191517094374, 1.1, 1.1 -12.285157679912261, 3.303794549705338, 1.1, 1.1 -11.900655033364673, 3.2020499992163067, 1.1, 1.1 -11.516285087345995, 3.0999789481453592, 1.1, 1.1 -11.132035271902048, 2.9976114689145144, 1.1, 1.1 -10.747893335305342, 2.894977872615813, 1.1, 1.1 -10.363846628045033, 2.7921082316712664, 1.1, 1.1 -9.979882739280276, 2.6890327776162373, 1.1, 1.1 -9.595989337726927, 2.5857816624294165, 1.1, 1.1 -9.212153773874117, 2.4823851176461718, 1.1, 1.1 -8.828363716437691, 2.3788732952451874, 1.1, 1.1 -8.444606754576826, 2.2752763472051605, 1.1, 1.1 -8.060870238780668, 2.1716245846181117, 1.1, 1.1 -7.677141917321726, 2.0679480003494075, 1.1, 1.1 -7.293409140689157, 1.9642769054910625, 1.1, 1.1 -6.909661089175546, 1.8606380310848842, 1.1, 1.1 -6.525895216967414, 1.757037423437947, 1.1, 1.1 -6.142112478744822, 1.6534733323034543, 1.1, 1.1 -5.758313670074484, 1.549944007434629, 1.1, 1.1 -5.374499825193141, 1.446447778141359, 1.1, 1.1 -4.990671580554151, 1.3429828146201896, 1.1, 1.1 -4.6068299703942674, 1.239547525737674, 1.1, 1.1 -4.2229757902802065, 1.136140002133692, 1.1, 1.1 -3.839109915335376, 1.032758652674797, 1.1, 1.1 -3.45523330023981, 0.9294016475575401, 1.1, 1.1 -3.0713466610035733, 0.8260673160918032, 1.1, 1.1 -2.687451031863404, 0.7227539080308026, 1.1, 1.1 -2.3035471288293414, 0.6194596731277552, 1.1, 1.1 -1.9196359065814446, 0.5161828611358773, 1.1, 1.1 -1.5357181606864574, 0.41292180136506373, 1.1, 1.1 -1.1517948458244265, 0.3096747435685179, 1.1, 1.1 -0.7678668371187467, 0.2064398579427846, 1.1, 1.1 -0.3839349301361352, 0.10321555335443694, 1.1, 1.1 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_map.png b/gym/f110_gym/maps/Spielberg/Spielberg_map.png deleted file mode 100644 index e9ef68d14b471ae811438323162d4d825244a18c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 62176 zcmeFZg)L#h<9u_8}K^rrJ3e`ZMl@5a&$lB@J_SDyn@eEUKz7I%~C*A}MuSME0K`k=xO8whB zO6}}7#^-)o_`E=)9s+)*fbz^c00i=6a)H+jxY0}>Z5$#~tO^S7?>ETF zby+>kUG0rWZjXE{{2fInP}fvC3DHXDruF0`A)hWoDgG&)`wJ-%qwqH^x3g$Hylp|5NZlL&gbQzOzY*iQh%I z7t=8m*wqq6t^R%`z|ijT?X5GS(MwDcaociG*xK6sPbtI#aaf`7bO(Ru=H{-dsm;0t zFvWVSC2L!5>UviRR||?%3jz-gPB)PzWNhjQ&z$7V01nF9ZSbeNc-~U6p75FV$gfw8 zp9-3{X6EKb?#swrgCVcBnAc{7l@_}$J_uskM}gxo`_rozbz#+cG6BGEH|Xe_L@xZW=tXfSRohO_Wl$A}JOBL^9?KSm zB)u&d80SjVDSlH`p>-9REW{;j;|xfZ(_)}#Gium;*(-b#8S#nl>dUhXSwk*LZoP&N zPC8;j0;c7rof9}9Vo?{0ync`QThHiJEiuzyT_lY!q91GN@?6{0#pkT`t2pSWUmPni zOA9cAWNZ4M!NQ9tpF6$BY_v^B623lp5%q|#D>(kUgX*BlppB;b#h3y!9~V$HrVna+ zUAA{qsM5&RbkXpZjaE~Fs!xTL%FQP2XTgDjsZI$%s8Q%A$B*!>Q@NU2QD7#aVFAfL>Vv9M zrq!y7Ulxi$@%%DxHq7}i#^_gR;YuujgMcyhMuC}K24_mvsTK{Hj&q{&VhdIR)mK%O ze~}$zpo7Q-TqvSnYB)^x)wAI!rn{K%BMgQzl5xXk(w~P{1S+z=f9;d9k1%p6-y#|UVlfB6lk#g4Szre zN=GIXJvzUr=DNMIW@3?2>o(`F)Dp`gZKMW#Ncvr=spF9%b#fwOaGs?iKU{SeGSKD8 z{PmFyI*8T?1xBaI+Zjq(!^t>=cN@*Z1tdu{SbisgK%tSf5iJr9BeVYC;C@|pA3Ny4 z51^Uo2qs9Bwr~9GJHxzGja3Z<-B*ntp=_@+5CeRg0AT~QFugBrI$PM=n9;yxZJ%WI zvC|w_dc&M5S_o+Nd8dINkI%2Du1~GD`aXAS1y3)SdT&ZI=8UzX!|Ac!dNDc{xuJ6^5DBPqJZ83}Rm z`@6or-ly(=ZdL(ApE;WVqTBo`ZdxXLtu}SdJ9W!T=cEBot9e*h2BFHmIRQ9^SH5PN97y0cZR@zJyzpZD>YDW4lwa9(lEG#VC zENm<+dJq>M9}oYZg6K8m@u)S}b@oz^zI&d#hDf#aPTdfbqQmamU8pS5huL^OH#0K> z?qx=JepE=exwTxVbCl{YvhY9XpzB3I%mufgTak?CS(Z14tG!7&CG*)-H2luUjGzaE z)S`|@MB{C%?ZZ&dmu<;_I%+F1AB zOC-}EC)>t}ACVaUTHTB}RcQ<#w0{N+Ny>4)JHePrj?4IAqmKKAmj!{@eTW01l}YaY ziLFs{>ExxGO}Tg3&#ypm`}b<^(Wb6Td&L^NA-wuU9dP6)fOk;w>oQ23$n88ThP`#~ z0Aefnv-y4rd3 zZ@7Z*7r?S~atA+3_w}AERMmFKN0^|J@00p@2i_fvh3)O^Y zCVzhwJW(^*vQlQ#Dxm9mOds88M%If7n(75KW@bG6oW1CsVSkZsi9xONc%nVsyZzU( zY--7Z1p{Lm7pJK2sP8}l9_$-iepqScsinL{{$Lqi4T)|T53P=LiBO*t>IsfA2NjM`PZHl`=;!{|?^{s_0ywXwm7{s^_FT0_2W z{0Mb>9rcqw07?}ON|ynkd=4=I-|ZRnDINX%Q0%bl;3d7+N=^Pgkz29eaE0yg-;)`n z`+Hj*TW@$Eibiuo+q%RV92MUAS0D>Lz`w`9&vuzae8+#)a>92_^)~qaa*4#{+B$c?vWuAO^(=0?i}_MlGd_8vIat z<9&WP`=pzm;s{mg@q*+m(gOwGur?HzR--Ui-uw4Y>C=o@K^#zEqAiLV3y%gnNI5hb zw)=}fJ;U9kQ(eK<^ zv+iS{34Z==u+5xbsM%2LB^zn@xg(ani#S}FS66*H4rpZ)21>6;C>r$JPr95~?O7}( zLv19mhvJ2HrFL|iJNxU1EiZ>FmWSvFC8)P2q**--f z?b()Z0cyUZGq4UYADK4ts#N%fHn{Sw*tmdc*;JVjdH^w^2xsolJ;fi1cQ_gAzEM$M z6x^O~=>w)`SRq2%j3b)! z$qCC-DekGmbFnO73Nih{>6oOo;p&YzO(NbB(gP6_x=;k&-G=ehz6$X=toSl;^EPA% z+t=dfr2Fa@fOUmC<+ki3rm5#qxpU_6(0}e=O8_xqqQDR8JGYD9@XLjG9Ur?J?k_uM zM4uO$gAsFu$$t(2;v>EX%}z?zOD<}hq?|Xp6{iJ6R6r5hAV^#vly=uU_JPbi(CXs5y`ire z0)px52S%t0b6G+FGDHi_9kNqD(?j(XL;8r6h*${ zcbGoEr$G>PyQd@?s+_v(?z~DlqxfeWmfDh(pVa_QBqwsA2;b?n9de5=fOsS?mf*wQ z@Q}x%01l{^m%Lu=$?W7BB0pKi0aqV%&>CoYd+=s^9SuDo6JT%$Emjc&Y5DT=C*OG* zcTmn5Qx(~o-7D0qV|_rh90gOV;98b_34G-Pm>|DC1I6W^ds{V~z0iE) z)X5xt`%>bF;qTh~aD#&6!pGqX*9mBNDM*!^(T&O(hm|izqd+#~*J+?=cGd^4Lydx` zkOQ+>M=(t$@*+EcH%(_Jqjml!3pXnwZ{R-CJff5wElED?7VwVbLz6XrrhDM&T(y-d zQuyvHb++KhzJNSpI?5I3tS~vkjP&5w7iuh|*+HNY_l(2-m&c=d8Z=BG(Y`*YLX%_8 zgIljcJoiPh6z|bNaENKOjS(t&~hp~!{(OfkKPLQZA z(Da(SdFVClac1BRYMU_S<_Jw5M{h0XTX%=lOrEVZz?z^%`#W!|(kJz#EPowajpl05 zSfB?yA2jI5-WkVtooQSJPX$@JuNTigz{%+9)5!gXUtbxm_KM|inH(5xHchYM!=KFe zQkLfxR-<`pR?pB{GR#Xee;!)Q9(VKRI})W#mkQV;N#(!Y8;taPPI5P3(!vTk@3#Ji ze5T}{%U@H7PUQFMS?LCnlF(1J5xrT+t% zXYk-1prJv!UoE20$kyBlvCZwIWI6jJbGyT`5x zSHIk60wiDp2})jr2J?*wd#O%pHffuD&{B?RDf4ptwbFBc5yKFlYl6oq-X4|2g;JjZ z>$xs={tXPLXNt1IS`VvA{8Ph`OpJ#qK*k(=u>AWWG3dGoNa(~D&ts_Xp1lb1IXtlw zUyT=%@2X3E#iq6K#hDri1Ev+qzXx(u;su4c7Yi|_NR~Sz8ASZ&rl`?cTKRQ{r={2n zteR;G+ip%Pgj24IsF_^nRW!TJ>!4yM03REE2d0xqO0Ar5ORsY>`z?4Xo~a3fFuG8r zsUhu0oQTHr9h+q;p~yyd=D5IAi*9ZHN|k@6C*R_NIM-rpy;|#&!ttbIbe+YTNs_FW zM1p9tMnJ-vXw>-1@+MP0NBOfQqPn)tRzr5S_PKgaRPh* z#>>LyF5B5UyRE8{*(&?lI=9Y&FSm%znVFdnESh8m;lK)k(APvIwQM#`vT$t#C=Szw zqJ+Wlsoy0vUGVX%+2bDU2l%W=J2`QLm}mJi-Ew2m!qPgk0);hV?t7TrTw0~r5- z_zzxo?g%C$EedQTQ=@%32N%aVGOma6!W_efcwL{W=4l?4_dI?a-T9YH^=3NN(5}R% zvT}EHVx~wfgfsdc?_MN8zJIWR*LH$>`b;22U6-d^8vu3DT#bxlT|tV z!LC9Wcq5FqE`b8SH*S=_JiT%yPL*~lCnX}HxP+&|3xLQ*hIky^kw-*)i`ccjhvT0H z;QsHY+?N;N&j8@?%!i$inHZ`dLTnd`%0WN9%iDTaV#?H-S7k3h;od|cHBR)9$vtMv zW#?bQ93j3M|3Ulb2~jlxTtLy$H3C}`k(c=CWUGRVOi^I_wAwI2kY-{TSsO%H7uk37(RaGHt=_owNG0dPHNuP#RwR0Q6f|SXfu6 z>js5F-JnPy8{KSe4+Z9eDPW=>K%OTa-*{{=K1Gzj7NDnNN;fkB!}VgI1Nrx0Bf-*u zEOi=yBnB5nkA!{C_lJR`CK2-FK2sS!iuQxn-D=VW=eP)e_?`6xb9=m!<(?{YSt{LA zWge=CFw6gl(wL=kSN;3d=rV7b4qG~dfbPLjG)%E>m!B@!qFiKs>g7wkDWs)h;iS&0 z!u#K*WoCuJnG^HV3&X?1!2Q2ZO@6ZzcKX#-8(vS|4`c^SGF_@w7nah!MPn~Wr(2QC0ASha^H(Xi{5JMw9Dzd6g~x6n0YDjIeRmU z-uZR7pSww zHq2vo6kafF6Mv+7F)wIH(6S`Azl3ZbwyF0`J!ez`t|jnEvmorUOuD7IwnKm zg&Mn+97htZGZrV8>%APL<7R{bd7ajV;(X6zy3ZYdm(_5B?l!bsaz5UejvV0^S zIVAT+$_LIS;~pFkv|Kd0;c6XpN+XgrnT?l`Aaz>03Uu+9J$(hi^=#6B)$f2z9H(fl zc|d12Kx&JdGsjoqRO;uhUKwWQ9#WJwkgCn51wE)X!GM! z9na+6fTI$H{br7{3WNU+``;q9{T9Q~l@n{xk57nHbd7Alb2HOif~#f2=tjy-CUVG} zlo{l8{ykAkGhihT84$Ts7CIZGg!J@LWIFgmE`L#}hUg3U6Yq)WNsESlEoF!jcIbJb?t};8u_(ZtNGZ*1w7BP=>XbLaqkYf zyii3*0{ko-D!;fPdNvs$eGNv-=`}E^+m#v#ZMFu_^-S9c-jsbsC(PJ|15Na5Y77TC zX=J>5UX!s$(J&r|M7iuv?#rlBLVos9K^!d{&`PLX4d1=f14T{Im(Io`0 zdg)h*_^wDLdc;`j_j_J;I@3_A2Gcb^|Iv#5h*ap$-Errn=gv=WG}bPIjH_`kAJZL_8EKbB7}iI&u;Lh9u=W;Q zB-|Fb;b4Q!N(sTMrm%n*^J=^QWnuGGZu)t*;XMFdFamhf|HH#VF0<5P-Q$tg2_2}j3&1;@jP=;e_OZr{!*f`ybmOoRp_wuJthC79FeKocS*hm!5MoDs`4mjCJD9gU!r5F1II-kxl>|Vqegd59f7sFe zyW%27jLd&I7WMzlx6JT5#XPn?PU3Qip}@G&$zR85_8z6T-5kW}+^0YR{@oJ)L)fOP zZ10KNJu>h#3m5qh%d)Ge64t9Xt}J*o?-#{$U3M?p$g{KK;swu65XJ6UUe)G_2Nbsj z|Jc0zU+(uG2!VT+1r+<$oMK_UtA=}aM6qc`cOsF={TeOjw*l+lG7)pP-@Ffi^hTmm z?LH3#c^yRExA~{x|NY>;np0N=2m-*^A+1OM9F@|zZs}viQM-XDH0WdiaeSMqzOI?4a53j9%44$O8+B)8IVM#xXl9J<6zR# zZDI$GzOT7uJ6}|CB5P;Yqv8hGOra%IR|;A8et*fCt~m9;rdK429N5c*iqlIq8d}Z^ z%Z4OfeR5B^D#t?;rS;}78MLzLpPny4pGwbozQukb{!=sL@;v^e{WE6VBNuqg{dU`Q zHMGz%x}nUF>bk}NbQ$4M1^iUf=a*CpWx<%8=aR+3@hJWhA%|<5iSN5oruQFa{3t7?r)0m9UW*wUR!(CUF&ERQ! zO&TJG%=gQZW0I~fLI)ZvHACtzOef)KWC2UZ26qQKYMz;|y=vD~4gKH&Bc`R_j+PK~ z;%5`e6uX~1UQPPyf!fMZD>;c$lX1~re2vR5{*iF)W4XBNy^qg%EVBD;n4uG=o*<2~ z?rPs$Oo_|qNpjrxh$(gNdi9k+y1N&xWPFzn3SMi~a{HC&yxN*IT>$8x(gmK0J+M8N z>|kk7)(wHlX$69s{3?ilRQvZQAx6ba75-18O=NAW270D`xT!pCA1oDJQmjOJiiTPUcEL|2ZeRUY$O zbKSg7)6Rc)JA9`zUE)9z(Bf%_TJPxT?2s90v-+pfIC5}0tNJ$E0PE-s_HwmZR3Fqf z0v(S%H(p)dss6C>`kz`8_qBkfveLj41NR{Cp12_>@TYt6K%M@D=Q47fUs?7QpYBH8 znVOF)uucemGsr4p)6$rSBdg?pHQT5>VCB~ee{a&V)-7WZp&Do6o};;m~53a@=pG@Q=t+=!B(xKLXKTl;q#&ruEB{VLLg(Uf2gCZ6RaivQO47^@t zk5Q5UK;uNdYtF#_ZGq#gk%Wd>8ZA4hV;9iVTB){?JHd{a`^NxMv(noo8isF8=eQL1 zz1tz;hutsGIP8;tTRyS*#KjA2wE*H8ZP5*u1`!Y*jF3G9-jhwV_;mpdzF9gY|_v({BA-($%f zTxi^9C3w}SV5syovQRw9Qc0DFAEuK*6!gPSFi^6{OV2d2)8U`XS zG9;^>`pelf$bP4C=Ta7+2?*aNbK|w~$)nJ*SA8l!UPe+06fp*!Tra5xYji%XKmo=V zS$j!vw-RqIVp!b9o!a;c>6NYniWteowWAnR)%Mp>AL6>>NMA`Py4&Y!VynN9r`RnJ z(-#5)F^D|t45q(#6Lol8LbQH#$9Z3i;eg0b%R;7BHbf<@<~jSK7B{HFay3rsYp(aI z)hU^tWAS}}x&6g^SK4Fm_ZjajKGuDUz=MD|AoFMg-5m?Kj7m&&rhQ6u^LIN<&O z+6eqjI?Y0Xqy@FRHj;tuK6s~Xcy&f=drfYD=bq$wtnbKxsRB$7=g&9~)|^*2LgUvL zVJzvGh@$3=rgL^`$H6V_n#JVt0u_4>vVgy37KiRPf1o{+y?2E&jqg4YB-mh|9@b@bt0!YnEZ}a}+VHCSjNA)Lwr+~=A+27kN zeH-qXgw5seHLJ*S^6ScsdF?h*pYL;N*XS?qUQWS)AP{njP&wH-<23GHmUv*FPXUSO z8)tA!J_&drlL-0a?^<@eVS|~@;fvC1JoH%Yne1%JjP_TQeFcaXC*@cAsXwKl?Pf`H z!$lWQmgLQ&SuKS4i;EfIQn!}EVRYqhwU>GKe)ct5L+cNa1subp@nqAsq<1wg$0~bf zg>*N5Zeaps^+c;)<05u5Eupy0ZzpR+WRVx-w*zdGuUw4x=x){6t@Z*DGqG>nct@18 z;1fH0zN2xCCa|1l^7~nvCZ$E;Mpy@D$`{ zHCXiRvP&0UeTqv{>6jQmYEgP?bF{6Pc&-qHhf2Htw$1K979j1~4^2!g)LCdcU`lbx z3(&ME^)J2%&PhDDq`Q8GYC_o*K+H z8xOU2mD;l>ssg%H(l-q+y-q$n+Zfyk)W?hiwxw)}qK&fxsU(j3l1dx8F5(3hk&_(_H~;(--ym9MvpS z7`WrrJ0Br^PK_oySBJV*cet(Pgsm;+7L`&$+WN-#`qRn{k&V?au(o_hkwW`_ba7ft z-20)_A`W4PXS2&fKdsUONZ<3YXw2nk!QSQsR;FFVJQ$3`Z!tN!TK4Hl^^H87Oi4g) z@lpWEBG%2uicX5t%N)G#e(h$|r&ABnM8CNA8Dte9HPM>Rj5_W#dD7z$_#+M){p)jS z(EN9HdAI6M7}D5)Gc#$h`Y4}b`HNY8uX_JGYc$q=gLR=Zf}OghPGGB{RO`0*lAR5| z<;};9?FB?jSi);u?6HuJ?%IqRyzF_26({Oql6KE&&S34@ zKl;n5tlDA;&>hz=W*x@MU=jJC#mj)GR2f;>Z~-c3|I<@?!vj{W)X5zbtf)|8>-D;#CRJpfAHKTS)$<1!B=$0FjnLFg4sbWwCl*Te>_6c z<&PK;v+7Q@z;lVqx;Cge6Ld!Prx5*TmPzW@Zjm5b>LgQ|}}-FzbZMAj`Hpu6=t1%!`aH>uI#ngTekzRQc6SHo}*E!+~LVZ?03s5+up3 zyX;jQ?>ra}N#p}>8Lk4vp7B@_o#-r@$u%Pd88gw{23$#_{g~2!uUJCtVULL~aG2!o zjCY^o|EbQT7}Ix05(MR1$tqxV&DaYhmI%m4N~t}4Gl8YhB(F5o{6lJ=3|&_!$XjMU z?K68G4)N<&FJ~|q!6hGAoPhD@fF#WKQ%pL{Y@_yJtBq;;LYp+!eVn>9^LY3i@lYh8)d-$N<>0>%uwn!6LCnBnXxd&{?Wr2 zs1>lS^S;8cAc*?ZoyKud9*voSnPt7%V1qbRnT9!IA^T4Y_7gdU3zX-+gmxqs26VxX zAOn|GZbc;+^CnNl&f|%z88rXwmgC)s0AuF0_l_Z^Z2=Lqs6p{GqWg$7oR50TAS%!@#mlmnI0!J9N-`Nqjbv?gj0b5HaM zo!zlnU zSxOm~UGV|BomiOI_)z|fp>S3Dn(q30XJDANkK5BPMf&n7hW$_9OyMg?D=7`_?AUrd zrlXvwWAGZdwk|apc(>t_GWmG zi$J@6!iffK{{@qTv!d}vNRnR#!!0VIbg7X_b|otqle3~C^xjX>XW;G!IP-5P6tb0k z>$z$yztV4-FO(6Tag#G1z6ON5Jn)zJj| z6eIBkm`N_e?<^f-(2p^FrgkEfxG_UAY`u!`mytq|1sY@{mIUWZ5gKzED~nRC*bR%3 zzpiYhR>`;59)?!L!*(pcQx(hMau6%6Sp#1fLzr)T3?oGoE#?=0vQ0V%c*F}Em4Gn& zjd!!<&q_E6;p!sdp|8ngSK5Oy3l63s@8(n>drCzDHD*xauyxAQs``M-=I?>Z6TPxvv_oXpl%HozW^RA-akD3|@#)7ZJY~W14rBrAFs)>^sq323s zosiBL$ai*h$ST}1HMO$}8ooxiR`Y-GJ5o({WfbUC@V(%E2V=gaef&qCCXs-!+wokV z()5eNclni7v2=@)=*)|3EJ~~wo1$UJE4juJI)P!ER6>Pg-tVV9az(6i5Uzp^)-Q=5 zW(IZ^CGLxBg%3?T1Sb=2{jE>Rf%)xjZT7Zy{n`&SRyVTExT{x;^);G|G&|AvJzfRA zk8C5we2J%TB8cRsJI96EI()1T@8hmpeStTvg0$WXi z>;+K;yuFcC5J}mtqxvn@m~JHhS+(JiCk%&}bcJ@yPldRmj&sas$M8dQGnK+|eagIg z#_?c(#==G}yVIR7!9Vq~lXr_C*OM zNE~Ob!7R3a!0g;`z%#U+=L{K~apNw$)uC5#1r(BJ;lA+YCyljy z<=hoaKK$fFZe^?V)bQcM1nXe$D1VpN);5A+>mKrf$??NZ5@7p$!g1$aqtDJsML}KF ztfzBC{n$@1llMn3$*(FOhpj(glDlxMomUUGeHdyzDSrLw2R9Srp~a$%H$?}PYoGw2 zyndp2IRz11+@9!)Dj$f2*(2?G@_MRD5jf`8!JmEW` z4cmPMtb1dvlSlsUAQpXKYC;-6dVm-(AQI9z4R-yU^np5lh@IuO(8EL?U~>DJdPj?+ zKZU72J-f;8%`@~d?3RUvqdBT0H?ws{6Jn>POJf8BrZ@IKtwFM9yejRS-P{A2^O{e> z)_H?5S7(QH@=Wx!Xbbyc#0iJwVZNVlV&hBpug;y&@{;WlU)XFg

16EF5=)ovF|7 z{n>8BF>KHKV^=&2!5q5ab=8Apm(mlav6(m23dbVyfp{%V6ILH8pMnY-CFws=*vYO4 zY{wdPqrGUd33j;;Ood5YL1DM*N)WlJ`BPHyYlDZ@-JMPH`@b&%YVZo98Z`dCDlm3r zcIUg~FeE`H_DnVV1fb~&-8?yH1%P~Q+l}Np|x4IH` z&o2mu0qwq2f}p+iiO0gQ{E)6QlM*`QorAX0pz`wDH{R@=97EOKmc@;0mG9hIxweR( z7SH8-aUrjjX@tmzqC9&U2712ObHFyDWlx_t zoe=Z95{eP0^0=<@>$JEI;egh;TFIoS1DkCX6WiOxKq)>J#J(Ls>Y1CLBvvX18GPvd zks`Za)2b)RU9zkmXEX{@ICcoeq)48=`B-ffYQ4BfdE-tF!znP5;{PeX zF~VALP8Fp>1svsZ+%?|}C)3@hvalI1h8Ee2#o#AFJJ2{LXKJ)x8gz<=(+EoM|cs@THT7jbdHN@Oq5(}+ImIqy?(+~~8cyYukAt>UMfd`u(K zm}Qj^K(@^uMJw&O-}3gl^-aCp&E<)5AYRZ-(xf_C&VrXgsITY(9|=>l4mQaRHj^CI z=8g#C`;!p8s(PI#*7}@7C2w?nk3M5f3hmD1l%ZX?ZY;Il;Nn`HKYw%cn@!6L(yDjT zMlUO{vZL7*9Ym+WY-@-aw%&|`3x*u7;toAs$Eqw9lnI!EJ{W?1m1shweUfZVsdFz4 z2xQh^-&R*rimTxqGmo$`z|)p>Z)(76ks`BZHgjVsld zxO=DA@s(b{?f5ir(<}MZpG2p&r7u7B&cw(3@EL^8k&~G53*kLjoop3p!X7#gn&?Wa zoEI4Wp!gO5A|usqp$%#Zbb70wUzz15{JR0|lB!-h)e-};z3@_e^YsT>&iCbFw_tnX z;oL`B7_gYps7S;PsPM~9mfY?2emX^&40ceMy&T|xmjqwuq^{? zAPM*|f7bMlT>PbJ@^k|ijmQU^B-LE+7ct)Koqi@5JH_G7M>Qe{Yg3VCb9GGf3ovaXoOCwr6javKZC+S_!Rh2Xr%FS-zuiUJg-rIx|M+?t2)X)zu5f;e+r60j zPMjY%>MfyHA{=1fl`4KK88Glf`~yVcr+a5oKQ^oVzRd@IL}o?0zOt`_4iE8ppNmC| zgVlVstbheh*t$F5J)e3@$RI9SR{5?ot`CCp0!zyWJkJEvy?~{24%10@L_bPlj(n=i zoF6(Ga64b>w5Y=PVX8dmE9_-G3)8z+L&nTmzyvr37QD#SCLYM=(3Lzr_r<}9n$C*G zSeL4MFxL)G0fz0d2!(?!KcWzCXt6tTSqGg%+E#&+Jm92p1Y+{ajCgnla1>fj?t%1n z-WU1DYBK90fK6f1$3BbB?!fM`d)OiEg;S-%6Kq50dAk^){CCw>C*| zk+Hw?L)mkDjB5ySaeE$m3Mw8%!pX#v|HIZUEs{MKFF$tHL`tu8yghVP-Dig%ay2UK zXlD7hA60WyQ}C1Xw>g-=*xmQ=_#x=z#mPj5tU(P7#?rpuQ%=<^tPQGrt& zT=CjvKJCr$3!>rB3uqI0uxlWWvj5~d#&YJqb~=D5J7k{3uw%m%1RKX#OsI8iWsyLr62iAY__o9OvsRY5UhPH`T0q=ZPY9x zl18vnEjPjY#X06<5wis$5FA_PH9Z#V6@nLSR0A%j5CM#fs@aR@)x{WNUxVIfzA#|) zjb80PqvH^EPoPZYI7^?VjeplcaOus*m#Zi4S$!-faLTN)Jvx8F@$98HD=0{Y=K-@O z5EV_nX}~_EtDR)1yO(21UPlHXr>9{IL*_aJp3k<7T#~)g=tRzizJ&8ZCtD;|OH*&M zuw<9oH74cIE}di_T<4x(krV)f1DW2_|DrtGmaeY3T$FGt>igO3I;nOj+Di^QI=*q1 zmdfMJ-%m@w0cpVK3yQz{-#XHJB@)%i5Myzytww*$S9FtAC=NU(?o<18Q zr0Wc=Wt2)gL*YcPmKt_+T%-TRU+onVJNhQ1DBje?%Xsw4wQ)c!xMH`E+wP+j7$0>PNIEo1CVlqUh=(fz?zpV1Zu zeJ8yz{VzbiAKT)ng{jDhIJLZQEfkt!$)N& z5vy_v>Hvqv!>^M4)@(&$u&#$R1q zVe8#$<4N~8@vyF*7sRq_q_p2H>mCs02sw&vwa$C-EPpcX*Y6bO{M2^XyCfjHwvoZe zYzbs1xHea6A1b;T3RP*tm3>rNlf;btfsG0%-?`-0M!86`gjuW1WBHTfO>I4LUh__e1x;T;;s?Jx+9**P(Wak6G;<dLL~k6hX6qJWf)lG!%()B7diN9WwI2_ zFfRmHC6QB#`Mho8PT&yr37ofO(AFTmuO}v@BP($6Y6#XP=7aKJk23Bs#(bgpQc)4g z8x{D?Me^cCr#^B54xYG@3j?%NSH(^d?Kg&afNl`xLN;-qdZ(JbSJ5Gs*7(G){edxgEapfF?tlhTZ@6ig z9YQ>_wtaM&94}HBPo8#%hlhuf4gS&i^kaX2zYq%6;rMhH=d;^~D7RG4OI7M`F@{Hm zwButG|2}3AMhCd+L|tB*YIXO?SG-^gEJjBJ8D6@ux7ll zd=L(^>VQ9tH&CMZZJP*_W+k;6rY6kxUb~BV(K^p>${DcHDOWPNk&$q7P zYQ(mr#zqi&8qdQ4difoB%}oH~j{~nF$E_=)p!Jj1sE zxzZSuDQG(aNZ*$ijE5XQGicWsTnRSq67e1``;i(yl=pu-$)oR2E)uMR)ZylDFyNH= z*c>y-vmyrLKT)uzzRfPtDN?_=92aDql(+`|I}+a>u#SfJEryY*p4J8PrkNCC(k;bN z)=b*)yQ)gebH{Ea+N^gjWTU236*${!+Os6guff93O7}_})xvs*y46bK*_Is;!2^B_}DF2Hcr!be=QJAW-X^BBH#LrseY}3#2+kw;J5D*n$DNdT*kDl?=!(G<1(Zp~+x6HYVnW2)0NF!c;X< zB@nN3`YiW723mU>FD^3}Q$EmOaK;(i+n*OW4z!qc=Ia?$puzmXk|h}~U^gcQVtS7K z{pH6lHRUNfho&z{%mCf^B$tlve%WXx7U0y?3(V~y@=6dA(TR0Z>BkQ!2F8^;iKLb; z+=a_cO?XAS`OUViKpuo!8PDauz3g{FovY3Y()#O*8TbS0?3R_8x@xLlb-m(@kpG z3-@Tz0Eu0dm(`ZWz!zZu9 zY_9+kC{T^Wt zBVCKc{JkVW(f_H@zT!odF~o+LwbbV*9;0JQ@asimk8*Po^Q-v&%%|D^yRA zXwgwzp_xvc3%0@xooYF%xd{o%=&mZ*(kXC)^oy=tJ>swU0M`QR($KXgWo5LjX)yU} zFiJwLcWllp3A7~y-cb-=T40kG;2)qwkF4gj{|{Y%0ar!W^^e0!cS)y|96F`*(47L( zB}hn0cXtU&#}O%MrBfP2x}{4(x+Ubl(d)XO`+0uv`(bp>(V4Z^UhBJZ?-{6j@XeXf zuiP7=3rpd1x6gJd9@9*NMv290`fSadS#DK3 z;`F_j(-cLgFRbb@Jv+#)c#V6MC(X^2FyY1d1bBUpS}?^YMt*loNR`vl6>ZI=XK?O5 zDmol>Dau|(R(%b#B=y_DdOLQ-3NJXsh|WhF-;=iHX1R)_Tt=*^BtpA&TFM>|H!{y% zorNT|t^f^+8i9og=q^xxoz=JRL_cVMgqadD#b`9noB$QpV~!!a*kR7$q`EvA8SN+JrMB1#OxUixi{7X& zHr)b*KJRn)rd@n@3N{V~TqGm4%JvLrxnp^L$8MZPp>Y-fH2O!KSdmmi(bkM*Y8Cf7~znEj!cG*_ zW_V;f2W^vb)oYOSD)DCz^a(uly|w@2Y3_2rA5*kOPTP@B`d(_)vkvw65-QAb~Y zf&38LtRyKS=O7Txd0qBPa^Z5rdSv~jhl`;7n9O8_PK8lKz;vJPXP<6)1D%RZUrv-M9N>IBs~TXf`enR-?da$Tb@MPB5AYEcR}NWT zA@@#UUrLYunSQ=Y0^Fz<07rUDw_7tmCDY9We4uy73MY9Dmboo=5y$zn2$J{?#mu>k zN~__A%)fE)2`DH?DAiTIJQ6s!o2lf)oF>s=a`Ykia z-+egiSv@VT&-a>MT^jbk+iQ{vikQFm%2u|G=ngS~Xc=btezNc$VHC>h=50t(d-k4~ zl41mhMgp?fRLb)50+#J!$wi0ZTzd7f^IZ!~?iuVWVO(Wq=09!3rR-(o63AvKl1jLz z!_nB4#b3E_dW0-4twc+xv9ydjo$3~aUbti`3;69=WOL))ePGmqnaRn$1jpm3IAMPi ze`v=d`Mg%1b&_@s&tn=sI=ViJ<|AHG`)Nr5#c>4T3u<8rg%5f2M`mhYorbx13^$RD z&4k>~=V!^vS8}4lL&8GBv?4#22BHh7JfYyPyb~w=tyXTGRKQ6uF14>9mmpNhvlw5+ zE*a_@Tc$flNNLi=09u?7-t%Y4vm|K7u6y&d8AG#&e14O8_gSpsd&mB9`Du#5b}Fee zBuvtY3b1Os4`RFi%;-1M8N)|Rpq3aBpj%H@7E6kTkFa?jvL#DS(+87OO}S4Q4St;LM| zTEnWErK@ZRN3OXY=RdGI_tPB}i3a-hu3_Ikszl7P0Ww2iD5LB< zoU=MISO+@Qa@?R^eV%~tQHQr$!L1(4E+P$$b5z3Pi#LxxW3$JFqs^WraU4Cb&qLlc z_hrGKoh6>c0yF>9J+QI zj)Osvof&oA7JNNBiPAy{O)Me!6qR!Xq;uamXsW844GH9ib>wfM>yDz@Z+?bddhp|? z{UQ$Y!2)Ce1nZJC4oLl)iGb4$=xga-wg)Nyo^r0-z~Iaxf|S%c9RSg0iLAP%u_uJV zoX_+dnIqrin`lE$@krW9b(gjWU?h2f1=?2O7}oT^`|+aFZUi zJOD$zOL)xp8aCt!aKO}j_;CL>;{HYB_sgIm>&2!)&}Hw$M3ZQPiL2 zur3irM+oWPE9`$J;TAR5(cupix#0?tbr`>)1twjQNwH%}m7@z*$Nv z85>IKddQFMA6^7E#Ghq$;K!2na| zd!0pm1sWL8kU~zIkBSn|xu}tw2Q7cIzoQ0B|{$luO9CUPYad z;}9<{V^yOc4R{ay`&BA<-;h~Ys4IEi9}{^ z&Q(bARt*Z{Ghna3fNR(@j1&zg$ja4fMt%0^3}PcOZL=4SS4Eb%flNd56&s+yLB)7N zVML;sjrq{kAOESZeVzvd*PPJp;XnUBJZgsw{ItTWhDYki)eyY~FPB~nfh(aNBWDOajes0#K z4&>d6f_jXR6C++opk}iI|FY(xG-DY?BU>mQbs}_wcGJ z`Y1Ka$KT6C@o*Vm3HUCk@ew|Dm5NH7MDx1DxzVmy$DN z``z!e)%pmtf+#p4P(g1X%+bf~Cin0IL#S4r+E2)jh{LQU!DcrIG%&5^LL##Erz7iw zzsM2}wfjx><01?y@NC%n4UO7sg+d)6IQlCVacBO&@brwCq)<1{Aw+ArCJj@O8ATO% zcEs}s6AS-nj8d}4zGJsl4I;ua&R&BNrF1Le6&(O~&>YvjaL*?|g^S(GSex+IYA-M8 zVm#rc3&xo~ybXdIM_!AT0OGs>;X>m3ZB!aOY@|xgdv?ta!gSl({##FNd2`>xh36ke z5r$Zugo5Q>N@)O! zuW@Qy8GiMfR`{_c?Jrvq6?~2mfP46RMfQt7s6d;gQCSsN#*h74sAwF5hl)AkEed7} zoR}w}cb4SL3?7>AC3sCj;QLWG3buD)a1HIVEB*Hf1R^uFypRR>g3#_pt>{XFP2+`T ziY|~*XYQdCAP)gmfS)SqLK9gGd@pM_Bg$x+qka@nOwh}ybd8n&b=${0<6*his%l%W zpXo4YK1}F*}Lno-$S}m zor)2XJzQBV!9E*Y0cE*_P0ttPGRgr^GQB+0W^r5(OD=8K06a3iHCV&n5OgeT^-(Wa z6+x0@mIurBI}GL9c66O_Fy7SIv_j74eLw^;6CU#lk18evx^yP9xdDNbSFg84#rHI! ze&>z^hEbGDKo-<`^fn1o?FkSxVjzy~?V@s4iunP5ajp8zySc)Xf= zON0uI;$vijg@}QDhvMa_HN;uiKwGrnUa-K0SbZ&bmT;j18Rs1d*fo}-_%fjBop_pk z+j6h>KPeV$(GPxDDF~XO2V1m%sFU<|_%fd;m}a2q{jCj{u_l;tQFSHD-Ncxh4DVdr zTZ$Fuc)!qR6uA+3UR-X|$Y3B4fC@>^85g}M&{%guu}YSmm(F@zsGw>6!^`as_tOD* zE!Lo+coBasLE?R?zH9S9r%9_vomE~uv6PAEsXQ)FGXrp%y1s-aJ0_6RSv64g7?j`Y z**Uq@`%s3YBEqY2`Pw-T@%o34phT@8zAq zD{c+e9nOb4)(mWv5vbU}zPV7DP9T68fwEnAI*P5{yd;2Yvt%718}d-+=h367>R_(I zkI!$C?hRe*o{Yt9%gk#Ad{QpVM>6e`grWhmZ6VN32GcHC!0jZEOXckC=qpZq^yN;- zzk2}`N~xLiiI>f0H_8dbtU|b~Xg|gFzXgV1gNk}=G8Li8uM3ZMc8O|y5ngh3jTG$# zg%OE<839I3Qv)b|!p`Y6=gu9OA}snW`=wjkO{Vv)+7{HKK(rVwB0`RyS|Xc;mZ#IP zlm_3X6?35ROE-BUqg*Lgs1ZeU_$GiKSeRTNHS)n`j}L{4ol9jHuh@W6>hmMm$VMMe zDjAsC1c274icZa2Im{rgbG^t2?)GlBFkOYr<8WwFSl*x>@ar1)&>_2gDoXk=v;eyY z9(~yc-g0F?7M4(Rj?2=3E+zE=B=EzvZCKFw9hj2J+mrMUDD^XO1urcK)wZs$)m`GT zz%^kBkFnh^G(bP}Z} ziU_0&x@?pOpJ5&^+3*!!21IlU*3XofAI*oW?U>bI3}$}^RJs9`W`Nil*%EP>N=fDN z!}^(qj{*;i^K&OIQ$}Bq05YKAm+f#$9CL|+R<<3`;{?aXd&&*iR(K(s19AmGB_B{} zMK=|A$e;ivne`y@dj(IVSZvRpt%0X7xE!CVcK@usSV^)p91wO^9C)NIUInCK9LA|jH3x-s|f zD2*|KpgCBQZOQw!#bpHf2s29y87r?O z?Btm(SfXH9#1JH_1YU6)ZFFGz8Yz*_VSvdsLB|g=<}3l5NHx=91oRU z?#kof-tS*I#?ygTkjAHkL#xQD>d6dVsk2Yalmu(EJ(c`L8wesT*eJ8k3ToMk7R=Ch zi?M_mD>mT%R6*jXGrf>HW8h{NKtbo=L_<@jW%D4}X+k7`b#TQ-Uq9DJ11DL~V2(1` z015CT1o)9@bKuw}ft;R+&tKCT?EgMEy3$v(JA4h0^3N4Li(We5uR5Uz7lS)3&lwiKhi zPZ16%`B+m<2n;D8lelF7+!SoarwZVpDU$_>o-BI-u>rrCPni>#NEHy_lP1E0H;QtBAS#zI5Wtk<$bddULR^kZ`$6e?)>p)Y~zWQwhzndFRw1!iR>bcIa1hp4Bb|9?Jr~BeO4; z(?5RSLGMyVSTbo=qsOXU(rr_t`_H#h?dVCHDn0P+o}pccNB8k10W%@aG8H)f{Pp*v z$rt}mA2tNMSp)Yiz6p?-8>7O+y4sA&J&hJ%B zd|4v;7_t5g`p+=`j{SGg|9p!K%AY1X^~CUMS;oA4UPmiF=c2F{C$HmYbZ@Mwu##+hLB*^_AS_x}uk zKklT>TL`gUUON~(1}S*dgo79p>A${_V#oxyzvLi}5qzlX=(mvmwAV4KRr0`|ewhpy zdX6G2ty^ON3d6FktRylxcx_Sp+mSz6&l&su#kTl*+HURA#&^FI+X3^IcC-7V->e3f z`*#G6e@XwZ@&5kbgzbv!o9XgjXEevef+8cV#G)WZ5P6-OHw%!WmF-8Q?!lE`?C64| zGWkta2FI;aLdBaYuw(gu{g9X3BN+f3Sj`UwIYw&w56J=Nf?43;jaMm|+^H7K(k`6b z{_oQ`_{Xw(724l2w0;cvk_zF;Sd0`J|C|IrRB!gz{5_0QY=@J;#_yV2w(0XGgUFx{ zPygTf+zal%W|#Zu@I~AndYe$Fa1U~}4b$=-5Fu=BayMV|78YYyP4?4##Y=}~th@Y5 z%|_ovOL!Ig*l)^qy4+~M9Ti~_~o>!@ftDB0t&Zrmp6G0 zB0YWW)gl4V77~C12Ng%5-fJ7UpY7Zp7Cvf=QN{S3O5t6W%AHWwZ$W^G`u>;oDh%R? z!&NWZ>rx&hlk`7r4t?K5q-WP8W8x<&Y)|#$iBMh{l^u-VS8}IJ@|E4H{XVk8uC!6tCz-gk>Q(D?J z8!UTv4h{|ohpL*1iHVv?cJ3E(G0cc#M*FWm=mA*f>FxUWBuj*7ESmzjraRcSlYmnI z0rK$HS8YejB96KWt?$+IaW;c`$0M_={H5oPwtnq_5`p&z_~RJ_2M-^7!}FMl+}hap z9bE2sYQdoj(B_*z5P^-@9<2VlP)7jyOOdY^$)OzpX=&0scsUA?&H*4AEf*~Fs|MAN;Nd8o6`?PjTFhh}4dqdPA zaC7N-Ud^DGAsUljN)q0qcuGZqSbvlv-EyVbPcH_N84cfCpu$JYC%R4v6$dQ+ zq{Tesg|6Ps1Y>_G`sixfd7!|RB#xJ`_~BwPI#+AEMF&@UJ0b`TLW2T<1c4`N)WrqI z^7+ui7QK-XKPaFkqN{&N=(p5({om25U9%9`YH`>j9eleWRXpR<&^LyhW zaIIy;OzR0AK|XHeq(0T*4-^b(5$Ql*3Ekxl_N`ma0^#lp&d*P2R<_24-1okFCf+47 zx@QYFxV%t|!tt}!se^#GE$iS!MvO&t?U-rnd~)gMIQBk{UCw`L`Xj&QX61ya=rQV+%6ZxD9hP~tYu==EQ z!~tQitw(q7t9Z zlM>{B{F+JGR(_rnryt`fZ<>cDI;dF*^fW5HKauJ(e~(?Ech`9!yw0M&U+kPl0HssW zG1fysv?6%o1P1oFy~GH;fPCw+Xex^P(E;~YYf888uC+%NgCcsDuNt3~3>~ROMZNt> zgf1P?rKIY$M+wVoWWs|7GEXT#svHLYN=KC$}^)a!6zY7;?`0$wUwyPrp&i4zSVUOedvbEevh2GgbzTI{o;kP zlyKCo_0fAxVH~|G%h(_Z6x_%AXB6;HH|cus7-QwSgnz|Xwa|rK#h5Ldlvb9CdY%h$ zJT1XQbPs>LD*x?csA9#jc&px1<|on-0bG0Ze26J8IuF2&-=4U_HtaC625>Wu?f3~t z-ujuCSt)H7)^Zd-q7m&X^?x(L;>(Gp{ZB4i(s8Po2)`E)4+<~h4ini3pm)vI>B z9kUlm;K!zVwYHM_-5{{K_YF1W+l$TTCu~l}QhQ;p8jqz+1ho$!rsL^ro5?bCHj+!Q zO=65aR)zCCYF$`AG^{nY>YdBB5c$zd71i4-j0yRv9PJ9%ERGNqyYeC9_SEdl zr-0EpW^>O23XHM}nf_O3%&)V*mE>`rpI`In#zd5eXj&Q|2ia6xr(#ft_*oJAT%r9| zvX)wPV@ly0OruL3&3F4$&ZNzs^Rs+S&P{1y$UFPlQyixiBmN%@`vbpLPttIp!nw#T z$T_DS@j#sGdV{8BRv3fU(q#m?t9uvLd=%!~*|c|*$Q@QGVmXJ*I8&wO-H$_X?%w~s z$^ZT)w`7_Nn8~-UAEJZVG`cG?ake&AoJ!khV%%5HLgL-x(@5a)cc*@!g4?V|Oo(rp z{1mOF%yeFfpr@O>G*HdX2&0#|D40TvdBvWWM5P#f7`S-)n^gR%M}8C(<;WNbGfY0~ zP)C6lujy?KW8HJpCxQbt2}x;HP^Crg(vqmEIO8#EypB|(b3goqn|yl#9OzA?L@=t6 z(Ic^Z9-69g>5HSzabi;bkVPu<$n8DG8hR8>qLXh767K94K!P>$uar&|bWMgGw^;I8gD zJL7*8-ZxA%gJ7m))(T?Iz$LcQNUo3qj3c>lU zY+Es1k{Q*zrn2!Wc^*Gb3=Deddm~8E_GRQqSnzgRjYZuGv2(Fw#@*HP*pYvg%Fcrs ztw=EU6BI>krR5QYFT+)<5O_2YN4`s0y6o5jl36fZM$H0+G%oXVyXWLx8POX< zBaRXresTa5?%XHJo7)(~Hnjna>}HX{(!#jCW9Fs%?#(BZs}6fxZAg$4iDw~|h!t~t zZVe0eDgQaeHFzHcHeFEGdox@O8T#OyTEx+GM-e&VQDG&w$sfcYNh;97i7#Pq--(9R zCetnjK4ux+<2K5UsiF-v>%@8?c~gV#;ERY)J|#}wWe)pq(tifJ7X6>G{xkBy2@YS} z;fEFZED3B6a|6!uRDHfn)i~&j5^a@ET77+?cMfE0{>d^30VlKbs+qA}YWWAxHK-H~ zzWQ>%bT^G@`OP`_gZj6^w?avK$@BJCLAV`6-#47Q>kT;BbYcbw)|?y649ba9n0q#& zoEA3Sn&$262KK;-ay5;c#oA-+@cKS;eRrW;qX&L8pxY7>OPw7b9Ft*&( ztR?t3>M%fWsHecF|6$<2x%$K4U#=P=9jLLw$5$K$$*~GM|IZ1fiCuoiSH1%pe7G=q z{|jFPcQ*nft_E%CS8%u9oj}?~1KZR|aZ#`c=}u6QEt^BJk6i>WP-^0(*xUY*3!RQs8f&M&9-0KN8EKj zH7i2TCeg%LX{(+CyolhhHL~Ap>Hn42#*=LROqhyQ(KyM@>oCErKOeU-Tm>bwhSUnV zC;oh-PzjebRh{Nzef~P@`jfjCC#zG<#|78v$Q45`*~MH1QPRY0U^u*aBKGd3*VNNgW(NKd_e@<$#tZ-kibno3(*2ITDUJfh%-ei{9=BP3{-i7xVXa>D**!UpJS3AZZ&rMH(a-M1_Xx z2cZK=E8YFi|DQvSk>JDcOz?K(8XeocNj>kHDWkF$J==UsIJ}bXB2)kXwsYH&p8~6p79}4)O6+CD zCQNr&@~?&>W6!#Jyv)o+s;aVQbX7|kc&8qb{RIEICAKz+UGz9#D?vj-0g*93C>c$I zNv`;Deo#$j6F5lGeNE1Cq1!b zd=B&VPT<4+d*|yt!~F>)+55qzOMiw&LFnMWC5OtuYYpzf72Ba@l4?By_vS>yqY+8_+R0m}` z8r;t(ipSeB#r%I0`qO~l`*1<8m@Vx237n%bpb;U33}>y;Yqz3kOS`NjKj%}B+h9C2 zCYeJU^1i&Nmao(HO3T8ejWQJq<%y$*{Nw1)Q0=^qZQY&XJm@1r95*jV&1K`W1c&`S zX$*J3F1bR5w}Q_;YB5rvn4*Wz?T2U^KWXQ?l^OA2^8+=_@=NY$R6|al3dE<{risy> z_Qe$4oV<1P0$3rqedVpyC}`i9I@a8NehGxX#?Dz23$^-s8IB>3+Yx2}FE)|N42f!X(k@e&w5V5-6)&UGwhbBa74Jhk^SP4|R|^eFT3^fQ zA;asT9I;Z5uAnR+-7_QcICCS>FCp_$hr<3M5;ZI>f(m+K0q6+GZ7Awd&Sqj`%K@ zhbG~hy>b}=apOCB!CfUi7Uz0LyP1_z;_KBHXa^Y7haQV$@B2AEa~%yfnQt@}5mQD% zG|LT&F;G^f4Oj`+40MsHSYC;PaCwQCj~htGdtrT!->#OUjzJvs>?-E{FM}A*0edSY zRk)#i-k-TWr`25*(co8Fw0@O*&io9b!$C}alhbqt*TI|Ind#@n?UJ!Z1f-ShBm#1M z$+mSzF(+QU==naENX)ljT>)Q}Tv;+;c79bSDC`uShH^VNn();oZ1*kmv#((|k)cg{ z!Wws(=q|P;n)_BaK_H&tWu4g^MwSwLtuTx3$381)mP(|cCjNQ&lwI{n?w0CO1pV!< zLKoG+a5N#sW}wBS&14@S6jd^X;WbU1uqP45brn6Y~u?{@KBCK8eng5iSO7 zRF}=Fh0KqaK8%#r(gwNoczpbW@H;&7yeqZ+!pCqufd#V5gQnD7Nu8f9Db`w-qhd)d zK~cP|)DZnTJ)|nNv<;DBIF1SsGVzMB+L|N2Y7qW~g<$%&mU~+i%Y6TR_+_I=;A)17 zyWH<*w5z>k0-EpZht*4-FKD48dhGdJv2p90+ieLo3zCWf?SIMqwx{g<1VfU*-$Y%q z^w@TBD>qA;v$g7>5RDp3OIPTE=uo?IGHM`b;)Z`N^&zAy4~A%x2MN z@&T3#*&bS4VltjoQf7k4%!^c)d?@;;ekw^qtDt^unMTol1KR}dz z+oSa>XVwUBPLmYZQG5D>QgTO((Dd_j!XB=(cjI@yF$;tKVWF{d^Y+4R#5=0qL9+SN zSaS&c`fVC;)NuU~e)zNdUq;r4UQ>ndF~*|sH(pZmKI~w#WVHY)Fm^WStB4N|vW-L*s<1bD8z}=>YKZp0cu5qG~`Z8-YMOMpB6!zU0 zxUre6v4}5gL%w0Yp&UFOI3m3!X>-5)UOYF9pvkB5tD zS>Pw8hEqQn<;jYNxejYw3*B?^fOI^1v#n#~K7eH^$G)(vp`QM&7IQ|a{MnOEBSpU= zxHc*2_@!HO4R~Hz=&(q#j=W%KMXQr1AkAP|W7==1W>OfNji3cs&S!Id%P zHzHK0oink*DZ2WxQr6z%pF?7HU>c>n@>Wqv!CUoS7(z7ulzl=_g<=sZC#; z-c7fE3xsOThurfamGWsZn*RbJ?7Qk_l96s@d004JZA+uaFW;PNgMU>0|o;wZu7wX@jNw-o$vudQ*{8hUh#EfnX|h#!8xT3M#(XHs!|Y~; z8AE(p!HdXcbn8mc)(N!MCpjiZ>re|FWGM@G<<)uIJvu>5HVNJ`hacJdzSh03L6|-M z%hO$WzGh(>L})~K&&6_sb?P=>P(Qo5EihiKx3MgCAuxJO&nsk>2|vLs2JmX^Lw@x1 zgqKSD?~5xTPvcGeuMHEdoasU11uyHDS6^BT@vKpLXIjk``|`Hs5t=Jv15IxUoC*qC@nXGh zTkd&KtU0?mu|q^QPdyVh1tlLdIr+DePHIpCcWfxgo>x*yg3!@PH-& z@9Mr+N<+fh&q7@2O$y2I(JFq-yu!wimx8G|5aU#;QFTTfZ0>mlBGqtMC@JfYSZq!= zfobKM&&0pkYWEC+T79zXudDW+dsx3lfJWT8F?0?dM&l9}SA_wdIe{dZ1%FO1ug%^Y zImixRNr-0T*T-hNYtzNm5-Us1!^2-VOBkI9g)E9v@N@X2QH~fImCU?^VtlTcI%BBJX#Q2j}<~Qm4ytte1zjw`6l=%lJjC0e5Tyl$P zeHewtkPj=rJ)21dZpQVg?dzGeYGN;QI)}I~Q1|03b0_#1R(q+qVAv(+?GL#iA|ARS zZBh47@LruDAPC0cBqB+6Su?s#`Q9_fUC@ww@KYrHp(Mv^>I~*pJ2V!MAcB<8R6(pM z8`ojAchQ^ZX&$B%!S#@1pKy~fG@@4%?Ez`$Dp7AlRM>vQmC7w zgvo#I?;tAJp?4h27dOY^ErmZ~@H%E@(-`(5r0xM-Eiw^x<1qhy~Y~+r~>?&AG1)QvlwAX47>y0HiXAo$UPKJXJ zRDeZv973fUFE*>QkG0nLh^XpT78;273kRAC;O?SlLU-ZRJ1J)e?$6DbPqRGXSZ8g_ z!F*fwrexU(NK^L$6=ZT$4MtZ8!>Z4^+Be>j22QfdQ}t6BzV_JU^pS*E4CaAq8Np?2prl-j2(uGMen#}^ z3G?HSL;1l;@~`2M8H^&H*yfr5L5qVdeB^~(rY|*!(pkP}Tt|7*#^v`;v@}~ie+DmB zRVpfB`*F1?Rp*Ihs3!>y^zz5r^siHb7~vDz!p~-^3bbANR3lb&Vf!2PUjpHDKmL>w z^b4#?d&StyOx)%O>mv~LqFBnZttIe^drcE^INC}xVHlQ34G-YDD{mcg$!e?Am6l9= zb?N%uKQ^Cjv$5C>zc;yVo>$Z#)qlCHB|QwCKy+?ql}r9fog~T%ch-^Fm@O=IMkDTr zOBF*tZjgNrr^SOXd#eUYA7Qe0fDY3uwbUyZ&33%>GP2CYlg`D7ONDs9amjOsXzGxN z;LXA+7}pcwVt-X90b+d(QfmIRxr{3%4Gc_5sk$TGuYcm1NohY639IL~TZ(H{qhM>4 zr!~?(&u6~DY#wvK)9Cx$62X;UJ0WH#=$03g-9b(qc;wzK= z+(dwX-knt4<{)VLDH>>|4!hjaT`;Fh8$|%46D$qp^Q7`;Wm&cMg3%+cci7jW(8UeLp*X*5-xwIhylBxh4$;V+>yuRxNqR^JhJfBUJXzV7@3Nrn>-jZBrW{QdP` zZ(W~p=I8v1T=A_c6M11!S{~;h>PsN#OBjN)IvTS-STxO{;R=t8W&&0ax+E1zHJ&J# zZvC>xIEbz(5K*n#Yft_D>?@hyrM%saeR1$9Nu)zhD_n~#h#&D=CK5JfU-}p-IGfpd zKkz_>*I8@hYbH5f)3vF%Fp(>IDjrzaAjg~$t40gVXkDPxP-#E1P^AEb8$dc&3zwz{_F1YDGuy%T56DbMvW_4U37&nF-!pf#TlE} zsmjN@xck{{CQbKM@;zW^M?%j&kr6@|qtY%O5&d%lP1sZa3H4{Fyl(6Sdc#x^}os5Ha;G8-s z_3u5E+JPNM%KNqYI9h7mpLu-6tqP_)_K9mgQ;6OT`a6$->7l!4)vW&#pa(PfRE0LI z+}U^YHb zoP@TV@xTF;Z}Ka=ax-~E)hr#>QhXFxvZJbH^a#Muk3hJHt)N?OwB;rpH{)LXofQHG ziB=jWFFi$~_Ox_=TKMUJ2e65oG*?mJ!%VQnw9kv4P9AoHrDSJWy%3zE(j}Avw=aEP zsFikO2JgjRd}0CigGe@hb0g&KFstxaYT8bnJ5QD^D-EPDU_57r2ahJvV>ESLF_Tk&S>v#;ryU@0Qw>{hA}|;_IjXB4cDqALH<(_> zNMmxkm#teHk%dlbPmS8V!1Oulx3!qbAO&lXmAND!Rkv_e{;u3>bg%ugerS(-X98PI z67Z%o?|ar~55CNwqp<;$>-B!U8On7(>dxk3)7FtiIpUvJ*!$`uW7_fdhh@|f`Aif5 zK-(Tf`p23I2J0*FBMLOz?XOEGP7XdCRm?**!zTIq8(3p6C2&OR|JVUdh=;IEnVGwK zOm%wa71N*ljdxhBjt7Xxz=D1KL&7Du0T)@GFBOyRt+UtpJ0kclr^ObixqZpfq)kI zs^PHv*ehfY5`eSHDUcL9rq6loojzm7K;U*ypf0^6?fXN?#&x!L6TN0SCkE!`^gfPx z9S@nxm4c)}?0)IV>T{&OGN7~-g|k}4*qCxc!lB{I>K$dm0L;(-dfVEW3Zs2wRVI0+ zymDqU3sOH2h^>;+B9#@Y!ou0~RB0!K{q+LDgmEc|J-qN?oWEYg#2mCQ2hKzS`T1)t ze2J+g9;0{rTun)M@@}rDX!@|b_G6tjFEavqX~o8m1&K?GUFHvSDM-{^YoBXaTvJTf z4G0x>zo^{n&)l5g_yE0U&x-DHHE<}1d~x-e=$L3^s;cA9urGiIlx3KyXGZcO#n%3Kfe zSocL`DVui2bkHfX=5kWnp2$QFnGBrX_%fv{VaQ6-+ZxmbBNQM9f}|hXUzea9u+KS8 z1}bsBz?A)0n;P+#U>wzzsQGmemI5+X*c#ELrPBa06MH0GyU%35@~tQAa$O^FiFghk z(3mo#Bx5%HFimV((;*6EDFy>JXf1-_skm$U+_3aqF;E}uvT&HZFMJ=(8sV`$p#;=N}hFZ#grg)+wW zo2JWJPVE!zo5*bQ!_mO2LX_M06!A;2DQ}dkYGhGC-DApupN~W29!ySsuE3E2y|zg%HRU|kWEBLJM2#|dBPm1l`cJ9qj z@VBS-nY6-3tfQAeNyHhl$UD^r4Te7+0xXeq;PCN<#RGYgk-d9^zd z{C+S1hveKw*gACTcFFQ_kn#WH>MFykY_>Mt-JO!s-6f%<5`uuFbZtWE*fb&~jWp5{ zO82Iu1(fa%C6z9}+4{ccoa_6w|ID6Qvu4G;?lsTzcpWD`q>H0BnZ>nh{}3_CL((?9 zqfe-CFWz(6QbGTX`raU{b0!QZgS@Dr_$QjWQ;8}-m&5-fi~%6 z5sUA|#REPQQJc;r(hm;fqCyg%>p$p;ch+2si}eYljQ26e@+VcFH0-r`UcEF`yg2NjOtT~2#v^~mSP>FQKQ732fb#Wh zm+F!6&C@-m2g}MB2|-g&i$_E$K%(IM@evbv8?XPjSkSJ*apG1hS~oXv@xy0o*kU9Ee)KI2w+U!60UoTpCb@izSG9)KH*KjvMg zyrK7;nvc&-E_a?rf*6WiH;o@^_E?+dq=jN&84DXHkvqGf?k_#%+T6Q|E7 z_hL_OI?;njc%@83#Tsip#xp1m?l0xt689`t{ye8x#${AQYDu5V+N|wTbi680(9fI+ z2C5ddZYb))$9ixby)#kFR1Iz7#xyjHX#83(YtrqnG~b{R!F%%2Dmvh&n`wQ$)30Cb zJgE{x(WdM`tcorBSESwj?t%sYLc_%h2Vy$Ne$BBv$^*C{>23&bd^}LW z^3usvjm7mc`oi`tMO`Ym+`Y(Y6}s@!K1E|-`6t~{^J#ILR8oU$!B=@HCXi3Rx{QVr zFsa1NX>ndhokn6JDJmG|VPEIPvq+gq16K@q_T+$sM(#%1&NW?Q zQLWkiiKQPymIt$n?z+tAVq}gMJ!O3^9t>uRyB7s8T@nw3SS)@#FzUEHn=dqtGu|}S z9k9va&I$G6-}g>Cqfx+6!|{*cm*yA9rw8}+@Zg5B2^bF2IzGT)RRxA}({KfbRIZc8 z?VStDI?ryd9lqeysaGF((UUs)(votCoH11Rj5Ke~@Xa3h;ELW16ddb0h>f7hGFByS z*%fQkMK(1RyBS0H`huXwW+mR33UY*Y18T zQd4b})VpJf*+yj!tsZp9Intnh$A3hTV1i~j1DmWnv%ez185<&ANN?QE@hrS&e zD6YSWLOOL%9>Y96M$eWXoq6c{ub(d*;R;4yTJwGOlw2nS?b|Cf5rFOZDkbkW9Fr3_ zt~po~Fn;tDwUBv>lMs7qFAjNVno9#=bGRH8qV};Kh`Jl=`C?fTA9mpCnDhi@mb$%O zpcY^Zt=7KY{qP|wLE`?59?lO?k^k;7auZz^`8?5A^$kM!>iF!sBr5BOytq7*b@WOd zgORH)ms0w(#S1@ta0&DjoJ?Tt2N~3J6w4jw%3q4fy{sOGT4r9RH{GR!HUlj(%nBF| zi=bu+P%vNfc$Gc(=FeZ==gf5tPo-r{gxNcM#9lmS_OcA^!p|&mi}m{<$Pij>Sa(V@ z9G4J`K3ON^(-Z%TotJM~ zFA2ZRn~TFYzRUS8Z4OaKa2{S^Qzy3AW&{ww9vN|>f6)1I7o6_OXQVjK3l4o&B#I*q4*YJMg+xtWW}xT=yJ|rnfZ22STFRjWofN z;7`PLPmiCGt8?2u%vEoBEmlQQXRS$5&2!-_Naom>C3y5p>Z#1>a4p;uF~SzQXIXS7i=O zP>!a&W$9yN6LD)^HJOO;C#kP(nIu%`um}I(vCvj3ZX*bd8rt<(ZTqvzrv`RA zt#He-D?^zd!C4CdcSg47-V|pAeXYAplWSNQjC%#+7Jx%~I9ri9@}?K;M6hCuua&o` zK82+_>fTJ0XFmhGATRbS_ua6=+>6#s3`WO|Uz+fU6oL+LELV|`LYlbo*t<1dH+5l? z9+fIfUhKJL#>@99Gea3?%^X*P~JT;}<~F((07k$}uW06kB(^-@$IPaVJ z5>;=sl0I-*o$0&K(vZ88^cLu#Kk-g=gOrW6vha9IGPDlp&9d$D(Hy&a)~Gk{iGj6a z-|Z4#Ou?biqw1;8bm%Kl=2;m61jl($ppLg?b4#NwWDwG2fj1Iq{rN`4xHbfdE$_IHZ=0b?c)}sWhsk9A)f} zg%6&K%6~dQ=)-#BIT zs(ECtrGM>@NJ2CBH~}Jc|8o_}*Y+i0B*xH@{rd|0hkQSsbU+GM1qROh`6U0$Gwn6E zSCZAskL9#3RY-%arZFgPyF*bnK_~u_EJ_&Wz7oHx%=Hs3)~w5BGW$Nh{fe;~oz`k| zaYv~>;-b0wymMx%=uQ?{?^?RtYwu(W^Vfph)U+h4JjN=%g#VYH5)`GM5(=6=#)JPQ zR+;3&6MXZ+Q_u|c-?ef%M8;~H6M573y=$-P45{pC!(1l@<4t$|XV6_wh+EnKjoXKI zp+`|5o2N{5PlT7fkS2N^<86&Eh53GWj+-`as3L6n!zog!#H%k*f-V<$x6Reqd`*tg zbvS$T-@5?zAG#F4c3s+?R1==dr&F5%}W7eX8 zAxc^|cJe!Umv=JPSorVDpS8I8_-)M**IE7I0I%gNacwdSB?xfzmX^@y0u1T#_zweR zps-nJmqhOX8{g@HF9`F?5Ep}wYZ&;_&ze1UwYALp-R-YaN}lseCFL8Q+PH)MguAEq zXDRQe=4-YlWgq$kz-b+3=X{=j!2eQkoAgx@EGN^j$--YKu>X0p?HSFi4*T6)RzU!t)0N)+|6if>KhO{+i(szx>7 zT?o;o`^MdIiY$I+Svv{e#GUuoJI#Ccn%%qS+1|A|_#TuoX`oA57(?;wNd%xo!Ba&{ zctCyoVi~wPg4qQVPs0M;4rP75Zw%72Sk) z>9~O4J-tEZQol)yT6@n08pH#*&r%aRmYThPY*iSEx}bvV_xShJe#@1Ccp5cTo+D62 zsr)^l?;zhm(JnMHdfDAr{~F8UdrR|%%nEom@Mh$DM(YuaGHC4I-u)Sph=2Xnma)iV z^Dupek}>p1^jv%K5qNZ&RdZ_tTqg%41tFWK+jE98uA=;GrrTpkC_&e3+j5d$K=v^z{Hq3;_L zFck2%?7`om33Zd+clZBHG5$e>WSK6slqYeApA0?+Dn8nC)vzc)yV~)hn1kYpDYmun z6?hJ-h-agj7}%l$xHq>%F)%zuVON{xR9FqFG(vp``}o^xVx7Zwm0wL5jG;NRkCR`0 z;}>WW1gtiEjxS|ZR_a>ni-RwtNgQq0BD z#wU#6xrxHv27s#`Cis7E5HbLjKxE5Q4W$@`&OvaWfgwJSl~>0EJVf;7gu3(O)!zZc zmloY|#eEaO)^J7`ICb)`boMq<=69Umwx~bkg4RJW@J10jon}80Qx8ROGHM^CjnyMC zJ-@%>;6=5B!(2k+L2tNHxPQD`>dF6a@XDDk_7DMe#O=iczlJUDG_`3kryBom|e-mzPvU}lYl?f^H>wu zK#sa^_T8c7MpmBszFZeT7IY&EDI~L`p{1VTU)@B&*=X?;7R>Oxajca4)pSn^>}T8y z+!FMWR9_tS4y!06RKN(-_L1y((G|+JU$>D;dru6$XV3$lV$MsWnob=2K?-J3S@MtL zm9Tg}!X=`2uM>cTxUwlu<&M`J`cPu7D)@d9xHoM-Aut2aI)o5q0$5-2ikxjSY9lRU zI#{6vB!7(GtB(R%e!eCqPW`s4aQzSh-;l#Ot_yx|5>G=iuPNLy;3cCeD)VMNMB+Xs zfQeo&ihnjIX7&e_Y9tSMaA5*bWUcE~PviIm91+%=6UPAXRyqG(?2#S$@oMNImmWT# zvgnjdEGR*`x1{N9C;(_u%|qfYsPz5OrN~OH1DfxZ!9psRIiP4GmiQqKXlSA|V6y9wVHo#^DON^0Y^x^q)wh_g4^BGrtA6D1cS*OsP4G)`4Pp?4>L}Q zQST`|B_Pb_XdTeyWsV^u)=LQmV5KMeas=MF)iL$VojC&my~}jiMYBqaPhgW}iB7c( zK#a98ptGuZ%RwW1avez!cJ9`cIkgT7D4Nos`7MtORGAfTW(>l(RJ!=;@;E7D!!F|?QbW7Y+zMbdrRo?9Mv9<9DykH={qxU^Rq|i$*!M(U; zjk)I$&lxFXS6Vx!JsQzg(dJ2reHLz^;-N?K1jW~A`d}{X@E&9BVAJk$@BGH#r*0dDkbbU!CQ{7Fns5~%XDuIA6?a z{oMCrP*RGX_z;co3B%ZP(Xc}YG}9eoPoX(_)TdT1EIC*n^$ zp6xvv7;#x`saX{T0y*#R2h8Y9kju2}IvJny07XNoqVCHEYqiUwi?(6@nZ~ipAoCL0 zufBMjaicgWk{v;}PUfqd7KPuFrSG=aPIMR1K+l$&(hbaP$TGgCnmy!-@KMGmEY|oD zT3@aRQEyjy;l|MxNPES50@D{pPF<@y4*_HT(R2DMY`Q?CJ0`GsLnk*vnRX-@BOwEo zsvYoR)bsiIr{^Y!IgUR-Toq0IPXJj}jTV;4&li;RjmIJ#q_Q z^ouAUjjzpJC>veGDBk%Jbd(o~FyUJIoX?~kTgH3OPQ8UP0KU>vS!2e|WY$Ve6|Y>2 z-iVyyhEK=YgA~jhE~?O)j*uJ-+Y-Hw1JB~i;Io#aeOuuHxGbiL`=K%t$5R2>}~oI zG>CyWfI1f|uMNhnBzijcTzovj2fL!TCwdA}S)% z2vhjx-Olef?h#+`uwj2xdM>ZH;nuxn{#^9J!iqlg9QV&ki6PQwmIse7oKJM$+xP-$ zoJXbKq#g$If;YNoE+KRfP$`~T4LUtECc(?0jhcTm?Se{}&~iHm?oS*I#9xXnpxiNl zlTaIh6?&cGUGU7yIUWPoauZ&3vb?w}I_edsx9~Q-2mum{{tD0A{r>7`k^5V`xer*% zzCoi?tGJsyF18Q+&;zfyZMu^-K4tXte7{VlP6=MGq^A)wkwb<%6{G($^l;)~ z57$0;e-OFvZ;4hnHox&bNW;rNL#mw9!_{QMkQ>^eo$g&gy(TqZA=~$lloo#WW8vS( zfrBhZmOk$u4n7=wJGEBo3iMJ{k>z?IyArKqV`h5)0t(b(dbkj&lcLn=i5)%}zKxGS znBXuOZV6+$Seu{}o1qDSt2fotOD5Z&0#E8p$cH-$jWEF|Sw!Ai#4kYvdvp8<8Ej}2 z3*C#F`w(qe5C7R4{zS0pr-GWjdh}i7{`!ikn15Ds0p^rKbhKFZz95Yeh^xK*8`;zZ z!8EhFYDoFd5xErlH>}(`tiU$-cMKMQkyoA!fzJas5&AtQE=3=WkcAu7`L}f2rcbzj z+tQOgRyn|>VmPmyU=jMAuxT zdSYBU{~Y%G;x$8n1TEgpt(y?93?W$U*Uf`SlLcy-C(Qh>q;BMG2`)Q*rwepk1;rq< z#r==XfdbPHzkIv+i3BcSmGjx*{22qKvs)_?U4?aCIC&k&1MgL9=jzs3UnxjE=w9Xx z141(e&XDN8-eq2uGYQ8VrAJ_55>5A4=HR(igsDsi1YL%#0-^hPi(-|FH#JsaGnhLc z--B29E?91*Z}PQAhgbQ0h!$JGfZN|q*L`=$FCnqV(vF1AUf{ixl?nc@P&Kb5sM-w| zv6-zqc|*|>0v*5WqglbAb&srotU#h3bWy$aVP5J^8!g#z^20FTolLUc>rXvQmQe6o zeUS~hexLxMj$|Yd#m;NkFVxSC*+e{p{|q~(YN8M(#oLMQP;90|W6BTL515>WRU~$; zws?2PTXo5T1v?zy+z%00`Hu>O8#Tyz!nczpS9(fBk2@#fp=U!>$GQ7aug1#1O2|h$ zTNGxo{W-e}$!fY@X_*w49%|~$*toHnC6*pyPy{?myKF)8@zv!`4_DnoEq6gF2 zbY#Y+b!9_xeP);zjzl7XxZfsgprLWss|Hf%d}y1#D*!+AFFX4qhirv+LtjSywT;V| z^NQ;@IjIXp67X$W8Pe?FdvMtEv*FYGIxl;g|LP>*(_N8q?ob3XME#^`*>d>aMIsp1 zg4%80{RMvZP(F<3f=Xavl0v zOgSQgeEoC7iYf4L#1E>KFnpV?D3xrbIF=ZBMcs}R6H|;6FB_Cty%BNQ^`zd9N4$CR z69h|*q--R0A;40|*RDL}6m@er`?N}++e>T(uEPgjxZGRkp*aA=h3A4CU3|L(MgH+t z^|&{TfvHT^-T9Jq2Yd{jre(mAAn)sn3s_lxFJ?JR{~(n3&@^I8DGN-fbtZkmLm>0Y zktB98Zrkg4sqRP;tjss@P?6_#1oG8e-uM(+;5k<-w<~wIa=$%^AT%ksyuCBWN3vj? z+(A~P4C**!#jNY8x)*r=-Kp8-j=0>nO_td#O%2?M|&f98Rg5ZogSMZg!R*GF&PKJhCE+QHX$4^5_0zWuAkZ|C5RA1YO$BP-L@MzR$Ufa;45sn|v3m$Oe_NQL2dEI*1 zaa?J+grNc8OQmf!s13KCwB%LX98n--U#b01oe1awZx%Ns^W^@ycfwD1cOe=eX71Co zD%iPAXOv1`fv>qG0U<5^?YguBlr?UVFl=4#<+Tw^>98*s5pEg6FNF-r8~&P5v!}eG z2Teem4H|>9R}pvYJQUj+X+8TWmk~a)aP&7>@!iH>8@g0tV3K$`PZzk1{U$9bbiLtf zuP)N(+)aoJtPeZu-R~Om?EH_KBv{dNd{5cOE_<<2W0$u@>E!1F-{(T%vlb~cxtSw@ zxDyatyT?aBDDHVuXM>M4LPtj&v+jAa#36Tco;5xOR2tIa$#g}c*bNQAG&;AR=%5}|3Pr>?lTQx{cH2r}Pksv{~o;;qUWm(jnOC_lV z064(s631BTmJkEWPuF3*IzR~gzku?l7*KyGd!{>PHXKc7R^LLA2Zp4ku(UYd0$ z()&VV*PSs`vJ5;Y{mfu}#V~FVE$^2kL>i|dpr2UfFbcDQ5FKbeFL*eC;Pg4xK2#!a zxw(ZVTjjG7Oc;!nTsSBCqpP=}+!V58V65YLXlb%sG`dTi(&CK&I=tx(XQW zOl6}*%kNuQ#(KHYzj%n?v?Pvw01SJ<;=64vk3BwmnF<%|xc70I}Zn3SCbCPBb$LDpk^ReB#FQ-tX^!SKkfM3EJ6qK8J;YvC%+dKIA0AT^*G9`1Ux&HV8v3S)i>UY3EKzQ5mN%XFn{0O|y1O5A#C0`jdi|m#W zWKU3tJAdMALR!wkW&120;vA+Sr}*N2&eaW_oUzOS$pr1~xb!u&*0Z^@0!UD<-hx^Y zJ=YEWPKXWJ_XP)0{Mv5x5UHmy?o@%+Ffbak*6UaTaT?58nGbxCIq(byJ&h^^)f53? za@%E>rkwGKf$2ov_b4qIRG#z+G9FfN4pyc&n(D38nxLA@;QfKagykAx66j4IgiU`K z(OkPzWF@!FVbe7U1Q_~%>LM9D)5!3{fL&_!6!0X+`c7hxrWI3nFM^@-|4&;a%~P5_ zRWwJ&R}k5W(i~+MM4}}sj0WI}&N}IzND7K!QM0>CM@`_{XL*lCGcMZDx~jaZ(Z5d= zwfsgD^7(my(FlCeElY2J^x}+0jQ@brE*T*kfC%1TYSBWb(PhLrafdY)&AGoB& z#weXwwaiD7oaaCb9Fpx`4H&;CerHEBJ#Ls8}}ejJV3}2!KeB?c7CJ5ZD5xsO|ph2)pS; zMxSC!S*wYbSL`gZI6EM!0u{Eqne4Cw%d&7=dGQZu???Mn^mzRZ^027yKT7ZR#{9YHL|79^n0yP>F77=xF zdJR3wi zc&)&~dzddyhzOp*#N#b9ewhEb7xO{nD5UFS2Li>>2S$P!u*q_`5vCqMiRqumSPy9; z5u(0*-DG`cfvZ-d-o3-Pf?wX}kC=NdxQ&e>0o=j4NO2=rQ7o7DHwm*Fz^aJ(^kmjmTp1Q%fTq5rQ!gxu+O)?egjh(2vZ8e9xzW9pOziNr0@ zgqeZL%((LZsjz7wo95dBj**Ssi+bqqJzrNhaq#&HNor;>P<=HRB^yHnGqKs|e5szN ziXaj;>CZZTGe$Ft270QBCSqU;t2_--MbSplSTXBX` zQMxIv+61KgAy$ZKa_h~YIfL6o_dcN%ko?Ckb~}`R5gA?N9$jZ~YEY!HN|nG!dW1RQ zEv}`l(9PaaId3uop{TSUQ!rq=+&XTLB>^7+St}?Xcbt91z@$H$;FKY0_QRQil6%#& zu&ND$fYA}K_XvYWA%q>_g&OTgK0>^m`**Q$Z)R!`%e2Y3Zzjn&)c-vg?Xk?}rN7*a za9s8qGXTnvI+1yEr`IUJH$lw>vja#JH_-Hc)r_FlRrkE7QqDxj&9nIas|9g1dA*tW z0)SV!$HFf#oxPDYhc!;aM;;*(3iBPheaqBCi?)e3f3KKlPUG(Y594Pu92m+#8U}bJ zAp0eZI8HXKQte$(B-I$%x8WsZqeCv{HcBeh&6f2BT!)g6Ik@7`us@m!hGXDMrCyrCl&-1I@t>n?ArYp5cCsK{X~2N&4) z6TQj6VzVyx?cT;kA)FLF6ezUT@A}HFHzf>zH}3B7suC> zlA!xja!(dls9GI{aX%Y0k6A&RH}zd7SZTURFu_0ty9{c5DQHOgGU!i11uwl%H;>c{ zpLS0@8~iW@iRg;TnL;qvkJ$(05;*+G_7!T1Z_}_OyFlfl}Je)4gZ+;@KU&=z2@-#dtYn91J*2|Omj^lPoPzr+^NK>tg z`z-j0&T7xFI&H!-y`sm0$4BiNPO~T~9;UtE8h(4G`?9I{TXfi@*>*@k~C<7R7yVOki$1cmvQ5(If zB6re~w>avM>hZLxoK`ti0&Z@$3oeQiD_hR)g|foOpP()?IE16)eR#y#C%O%dj8)pV zDBRNPCVIzX<$|a`dvbd&SbnVK#M^2cik=5bYt+nJ%=zOkf5_VYJ9sRK>@USt-J}Wa z6?{CH^srHNzw5BW6i@9PHZK)nI01;nNLsOZ%v)^Ti2ke7d_{nq#iJR1Vvp>&_TNLA7Bgc%ILGvgI*Y9?&NGE`vd15w~Q%%defX-I57(Au4FR%F9 zyheNW8U)%x8Y)!JS&NKWU$Y+$6uU9q3JPyAsUNJy_( z;bCbiYC@|&``Z5<;YtJS__6eb{)r(CGCI6kyzdztd1v%b1j^vB@`p6NkV^er4aUweUaoQ+WIB!B4KEY3`%8AO4Q;6W~59vT!%IY7N zHtAI>7OPUSt#GRR(x`!9tF3!HI3r_#x6%;mLFoeeESl;~xK6L$js|V9N+sxQPn~_ju zu94oM0J$jWskj%Va}Ew$fH>`w=<8s1p&e4y&E!rZe#ODNRY>wr@uDVOfRVcSe6Yqo z0%by-lztantg4H-PT%X{c0|cvY4|2ILR)>BEKtX9T=?pv-It1B7Pk`f6MS@9KoXIx z{Gq2B!jM(adHSC7hOjp#k7(PAJMQDyc?6a3)D@*0AsOYHQNHzy8KUc5CpwxR3-ongXX9LHzn0>JbIwNBI-Z*n) zISBc=weqEzA=QzH+IUgH9M=jBWZ}@y@Hdh=>K2Z!r7Aoz21F`w=V_X-Na- zkmTn@0-ms`ZoaQZ!QV5%fguf{>#l8oTj|*;r4SQEQj|A~C>?%Y-AgGTOjfBaqgHA$ zqsjN?L!#U%fJvw!1D0d;CAc)~Y9=9|56cew8${2vsrFYm>%vq=fbv=OsBWcluK>6Y zhRXb4%RJ2rLPmXHFI5u}%nq3(V^0RC%CVX88l!QLweS-@j0x?b_&qG$9AImYXJ{M9 zb(FiKj^oxgtTg0E;!k`E-PFvEagqdBh$^+;mQP5`G`~qo=axU!0OCZ@k17=O`hySH z%^AbXFQm~snnIDzsl|9o?iJ2S>?A`2Y=BfbS}^13f$|w#`y3t`5TK%qu+nsrlLxcs z>VDDN0$_HCi=zdmcVb^?O$TN1i%df9l7}}SgB5#&NE^?U#Ev`bY@baKDnb>=?+ceB zrSz|U1)#8ePdIrF&B%r0TSgGPyNnv057kR!T!rVyep4w1ER^|VfpZuc?`9-Lqw0Ur z1cNLH&hqQYE#vJa!Zcz84alIq%+w(Hws=An_(u99S>@XEqKV9cY9ZBRfiK8E0f|W> z)LJ|WYg)z-GgDP0JwZ;0p5)TD55VP$`Bu2cvchSUJh+5y^eL&E3Q7ekJS;lN^>g#N z5y)D0Dq#m7mg2$tX^v!HjFf75ZM@i^a+>tg3C z;GWDmQC%zW-jxU>79GxW0xt8ALK+f8dkB1Z(z$6EdUgac@nLV261Ut2)e=*oHGLS1 zePdD-UE|=LW1&d*l+NIZHG@9rNXi#NAa#6#t3mo(D{nin37Wb@3WwXOSyaWPs4BI^ zUBV6X&F!on&Qfkrfyo@3k4WxJIjB|Pn4U8w2$rU?gcrzW5am@>g6 zd7EKrx{4X5RsuYA7W$=V_g2>lz8^;&zlbmiuD?EOMvPkF+2GBLCK8n@;VJ`V>a5yD5 z2o&(ax+dYV2JtB9@K*0Jo1Ct`$o=Ftda?wr%`s(2a+#kM&(E%}Qfh;hx$r7GcoM); zPk9^~1F>2W$1?(gN$6W+tIDv7=p+C`IDNvjy{$kkpZqD1f_)4~W2Tp^9XZd|9aT*K zprMPEK|)3kM6aE&!e>QEizvocHudnZtu;s(Bi{*lVAP7_0hQx#yO3N~VR~@gCf~AH zpEFq>ORa~1<2s^SZ_t{fj;8(<2+Q*D@)oseB>) z3V7Cx(*9KjG%5PR6cG#1vFu*Ee@{s4XzA2eZ-GuRHhEOLjH3QkxR35t$-%M@x6}zTQe$ zp?6Bs^Hm;64XcAt?l1ABA9GjW=QN+6C!9U|U{$UcX6m|(&2WW$rEj$bMsD%p^*PmaDAZD|m*Q+{G9?l}7F(`vX zLIg}WzFgy7w8L@;2z*L?Ruyt5IfFlwnrQ0Jw5{tRT0V&CeUUeiLN4ULM?@k3hF8z0 zK~PMMG0bJm>Go!rq? zJ2nzEj1!20^a)pytfv$D_5DkVa}xI2U5i3%Js6R=G1Vi0I=(*p8zgJypbF{0Vo=Z9 zLIa|yI-y|?9HeW)p$gNltTI~6qf^}!af}P?zexQB2}y0J>^(q|$B)HJFg&$FiP!0s zQVU1q7e}Krd+*%XxG&9!4oouPhjdXzFi&c)z?D=k}HsQJ43FyQ>u|3L`K_(C2S%EEADgs_M_wh$wqf+i_@Vt?-VB>3^r}j@# zxe~fxpuF5^?A_L7zl8sg+)e#viwFwLkVkt;6v$twRXhlfUvwgV}BQSe^F`2 zPyHX%?+Ju|4|*9+ujgSpRjjAIGIwMukLf3FcUrYjV5IYoxvKyt-UI}Ji ztXU}X?xABn2Gyk@_WUCdn8HD60h9@-l=!3&W;qXaxFuY!I`)v9g%X1cMN82Z^3Y1lMAhmGR~U<5 zi4a<7w_fa*CuIcna56>S!x&6o0>=h@*`dVc*Qu-B<#JF0jn>6 z%;*8YK_0De)8U}dUQZW9(Y)DL?IAlsLJj@-OqH~I>Px&bdgIVvGh*L70=Jw{fpUC4 z%f1HeA1sP`N$KXsHhzAR=gHOrr-6lb;U1_nBWyV9sOpIehwYK`n*qvF(1Jtq-*}nq z)U`+jMZv~S1=`~1W`xM^X^2quOHE29f(;EaUOb%D2`a$@Zb(qezls6wC}du|G((kX zL)mzW?w&MWTOb* zL&^7ni~semF)K|7O_PSQ8qJawYW(7Vs-m^$WfPgI22?Te0!zsGSD&x1;wDl(1MWToara+wdLf#uH zN=_WjRyR>YZfU{|n`VR3XQb7Nc&P#d$od>P6}p6uPB?a%7)%|Y&dK{B*Chf1ndZ)~ z_U_0`NIboh{@?<#QLvD54@?gZxk`fzpOhuJ(h&%Q8xtg5KLtEM2N<#@xAs)(N~m8e zc7vmis6G}X%&-mk+5L|JNHv(A zDo`c*AAdx9@&G`IyblsDWh$=-VsB36YoATw=~kT>T5Zt<|Mk)pPQ72rh8zE2u1G4- zSi!QRCXNL~#Y*V;uxY$FGmfsynbrL|)cS0okC5`6WYrO_kbf%14J4q;T7NfGD&Ad0 zwlmfPn9jP~>DmrWA(pv=)58M61*_E3VL(;DL06`bbTNFn_-tyRu{$jNLDD^Y@`)G>y9X5^`rvjNCPcItQw1DeO)Sy~Y&pLsdH zy#uv(6(A`>SS(7CZoB0+>=i;Hs~sUM?X3u!xQC8fERI{ZeZR@HU=Gaocy(FV* zI1F%LR;sfa|AM$mkR%YEr3A^<17L5=cLL(raolw)apB^ajP6swsEy_XLugkn7vS)g5s3$A^+L^zhVr_&5@~ z?eCBL z$9%wePIBy1*@dgHQqqL%PKW`LlPUz=R(N2GL<0O#{%;X)97B?96t=rpEQUNT_*b6P zN$LIs|AP4pB%MwDe>n4e7y!^a9lO{a%7Y&;K$q~2sQ5R#-0yX>SZ!*vADmXoYK^Z= zs&v0F!ZERW6v`6_T=}x9Z$;PI$ya*X16lwB7GEJ?TG|UQTPfj@J}_4Mo!Jkbm^WmA z^Z;gaH=S=j2`31T*Plf`pTd0~sK;4FlM-pJ%^K0E$GOc3@3{)74e~HxfmU1OUGMvr zF*iFlG1p&46e;B4WA)v-TRbys?-Qu7^~V96FAHLEYZQ9hB}d``*CqCCYM|N9Fi6Vx z%$Wg=npZ9~s{5Zv-=e)mH?vkqLx`N83m!?>F{M?XdlSJ5i+W}k$@4unUiaTXuYE@L zFP1A1dQ;DUWeAsLBzRRgO@>Hw;h0L>T^d8!r%k(wrP>RP@(=k{^RN_vIU&u|PpJq` z_&{hqIW%ddcS-?Q?+TBp`7d9ECf&{!&7l~1atLO0>zzmxy5V;ci2yK1$bj_v+pw}5( zz&6SkQdSIM@A)%Y_*o5PX&MR7_)^sP3^Q2wKWHqe7%&a1>8cgs`-%X{1+k-mUjCKV zJn`B3q~r=LdkOvM+b)KTPla|b4Mj2s?NWv%k~)+Eni&2xmSyP)Nd0i?Lopo@DSTtMoAzI0XTPU&H0_e$ju z2KNwRlpiv8BI}o?6$~rP7*c=T!C?Yv>f{~#dP8{!40;@AG2;jgYEVj_^)**}>t-MX z8Vu^C;wt7*fbj`N2cZcr`~3BEo}R1kMWui<_fiKM;{KR=;S>xs42OwVc#M+L+sNzh zaYQJALjqKyVuyz5g|O!DCooTNg&fl%gZZ%@@8c~v9WKltk3@JY10V0=sv2W+_W0tUSa951PY4OdTIhDx&2&W#2llT$ zOSRoO&Fzvntulc^Bj9ch6rca&E9+6ZjK4&-HwusbU*`E?`YhJLr)Q;mx7CqAp~7H( zz~Lzd=CV4`RR*HB8xfjPw-g~Sl-sv!N4HiBjS9UGMbsBhDxWX}Jp+Ln;mCe)w>t8! zKRi_X#zVr-v(KS%%fB(v#Jmi=X+RMt;Zq=>!TzZVMv^|YAP`=H&f++|&o!&ZO&z6Q zeTOe58E(+^KM`NMNCXrb$whELcR|2`9vTvv2@jbOC#6`T?WoHd&DhUa7YZFy1ftCy zY#tUMFIfHMefVD(5)&loz-5_9X)gq%bxqk4HQ$3SVSDm-_9moU{C3)Bq@e#Yt4i8A zH5IR{LNNXjJ~JD*L%+SLu~O4v8v7mz-`G3^ziJP%yrDRB(Tx@SaNP>EEOqxg!SmK^;J=bo3@1C8x}$`AJf}HmRKW z;AX%S{wSRWO}{jwYJ!QEYecYck5f*u55R=+oHEK*l=Z$Y8&u@+SC&FlU3fa_EoRY) zZi-xh-h9kig_9D=sEvn#OgM=PKUe1gITu}5{ENM=s-y3;M-6|IpFEYaWaH3Za`V2G zy(MUbgEYPoa&4lZTpv`G!kV{!#eVTb11j*V+&oGn^;5(DwRf#wXbW2(dwJnn_GFLc|0_ z1Z;hfa3khrkcwiWhykB~ASy7YvpVx({($+E`}I8TZ|~pP``mlZJ?oaWoEtclx#!=T zPSEC|P|$bmpDnVjjl|zI)~^PE6KRdpOJIHSw|8%_khB9VB!R7z{cpI}|Kq9#V72yD zXFc)W@}1vvDL8}OtsKNOA^*b53-}Xq^XZcpd&Kv+j+-$i_p1Sf;ipsgFp+Wm(>uZ* zhUPPF%OL2L!ymo>?h((P(N~b|8GqeE>OZwd*88MC^T6h=P3-wz=QC*P*Q{+^7&84+U&&!(Y{F~}0>*dv{_w;b+o7s*PVd{f|- zQ&|oX(fTFif8GpXt!>Crxzi^rqiM{o#yPjGTDvjUp9T&`pfm|Ox1-l)V=#+zU7wL?cf?I-`17U=hRfb5bv>hE(~}(> zQkidDL0M3-N@Cn9;d6t`ZtWDuQ_oLw8g2;Y<@i(-eNlu{idssH<^uNtaZEw7U+ml6 z<(H$o6G#rt+HiGdQ|ZJ}=Cc7--p}^d3zk~4hAS5)ae0mBNXCWlEK{<1m@AZ>NKQL~ zK)nyhGjBs^c;T-G*U;4+2eB)H{NpTDvaJ5qg2Vb{L1!s=L^S*O8y-;-GsBhFuG-kGEW!0Hc z;ZZR%y+fGKoN@+<7R3*(j=4cCp;HL1OD)=^9-U(ooVQ@{!P%RA0>9d3(w~du5DKRk zDmfv9`N8|ssgIYM@oFyH6b55fMJ;;HM5n^!p)&1#aR0_#-GT!_<0r23rgXs=4AyQl z)c9PetzYShv#hM@96wW}(|dGBSHuPKr|~+G$p~A&sqvY4V+c{D7S%;6{)o-@Zp?wP zVQ_-JV4&0Ui8zLmo<8wRM~Y>fAmPts8@i~(yy7wv7zziai+r5zQb<HbnHy&K&8F$nIwk?mBu4uR+C?c2k@(s%o->7JVqiRiW5yi1ROU#J?E6=su ziCQTUKT3xCT}_#U{}IUg;qL$o^-g}HNiRZU^W9A5gZbDnat~6Nq#Y5>Cc}B-UxVmw zN&hR5jW<#O+xr44tTsb^eerCn)$QHG`J5#rYn?%NxDWkz!|l6d>Uu(}B~<6QNx>|i zgJj7CWtZ}o`j|h_<_G-PYkdsktbvPf!FLG=oE@nN(VTP)i&j{>YLE!DhQ`opMMiQ1 z8Br)TLwiqp-)6!LpmF;O&RCwP@zPaT?EwC^7>R~Gd$S17ss;ZMNJQG-50xPRpw^`a zU6Vd6z=BI?98%s4;XJ*hw2CcN8L$=|5MVexYODeoyF+D-iHK_*P#j<`g*~^)Wz=Rg zc?RR>Zd(jVcSf~J8zBck3QOT435B&XAxV3oefFb(065&|d3 zrUJv_T#G;%lA5+)hBeq7GW8iliuUB3hI=@S$PIU{KmTi1E$ulPkpC*VYo6ihZLpDT zW)p=WWt05b5hH2hHsZon$OghGrnwz_28p5qxYydU$R&%CSd2`~6Q*blcf?t{;h#c$ z&tHq~zK^v&@HgK3d`5pu*)e~&vZ0P-R0KR8u=r=e>0!xS)6udvz(~2*Ly|75?+!@- zTZ~M2jLtI}SJ!>}NznM~fu;9brBh$rwd)23e)EjAVQ2zm`8DrS@YDnHAdW0AB;ikI zCyoJY*gXEXi_zU}9rMiKK^D2;U{%R6l29I!nlP$t>&j0otEej+8UmF7LaAXjtX}JK8n-@)C*%ku;4lEsI9{_3rw6DbXlp9zf?1uzFtD^s zr+ReOVc^^PmlobS5;Q)nXY{u+Ee3VYV+mD27_AFk)sVP!#|uU0oBeXXEj7}nq`}b` z*-%!5b|8^5vXN)}QMJD4^%hXL@|0n0;`~8&pQNP~vjGaajczVX9wesV_$o z2E*u+Qw8$51}gKBhk{85NR*&-MrPo1Jhb);B_;G2yOesZJ%VdX+_Z2T7{PhAmFeWK zdBR2UC5!3;_b8S1SQJ=vylih3XgRmH6o;01CUN#T_I&49?)Fp^<5+UTVFcXUoO1vTncEJ~^j`DJ4a_O-bF&Qe1XMJqLn`2$&PJzjD^Wq?n?cSO zm)khCNWJ|kZu?xZwzKrD5k+abZut~codldl#Wu@9Q^G)Iuk%XRoVt&3y z#J?2@ahgHEoy8NLwO%~zGyU*_WvZ!t_FIZ{;XYzH9CR#+l*ck3;?+JA0!FLFw|(|n z0Nj7rXTb|-SSwxIdx+-I@N@U(q-ZU313-*v5otukawQlorS2a58Me|MnfD(1I4Kg} z7|PP5acv2H-CCf|_0y4EJDa*D-bpxzCP@Xs17ccASj@sQv_@(6;lEg+G$HfMsc3jZ zu3?jfrq7K6>B&t7c$E7J%CX7u3sJX z?qbezqGD7tz)NWQhHP|Fn0$H(qT;qe zdx3g3*eZpqc~&;wbw03OCdB9WZE|M8JCR{<9cx`~K8P<$qRiQ^Sj3ah2Fbiv;s`_* zL;R>NfR_gRAy5wPaKJm`&)(ruaBRIZy;+9E77MR^*5&I@T4`q;SeI>`ZlkJtgquczE{c?3tTC49gb#+fg73_T{J%4 zz6(+T!}{9sEV$HmW_!pyXGo&xu$o3af|CMQu2?>8B`A;6psG~B*1WUSj8vQsO=Jyu z=#8>S&UNKVAG%~QTw+)jBxZ~#+&r>}5Ang19_mGBj$*dH@wQl=$R-+AFQdnJ_*>5F zZsZ(31_}Y(`+n%v2$i;Gna#v6p7U%RWamQ(|1?AXKM2z}?oEx$Zme?->#mOR*h6C7 z%&hvrvMsIAPKPf}mraW(azC)E7E0cwXf>FV6?VbCEoE khUa$pe46`=0@p_$B)l(p@7Ndr0x94;>Hq)$ diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_map.yaml b/gym/f110_gym/maps/Spielberg/Spielberg_map.yaml deleted file mode 100644 index 23975772..00000000 --- a/gym/f110_gym/maps/Spielberg/Spielberg_map.yaml +++ /dev/null @@ -1,6 +0,0 @@ -image: Spielberg_map.png -resolution: 0.05796 -origin: [-84.85359914210505,-36.30299725862132, 0.000000] -negate: 0 -occupied_thresh: 0.45 -free_thresh: 0.196 diff --git a/gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv b/gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv deleted file mode 100644 index 5e8f9232..00000000 --- a/gym/f110_gym/maps/Spielberg/Spielberg_raceline.csv +++ /dev/null @@ -1,1695 +0,0 @@ -# 17b4de0d-c737-4d0b-b937-32bd2ef0c95b -# 603fd3987364b09f9aacb70d1ed12c268e24dd56 -# s_m; x_m; y_m; psi_rad; kappa_radpm; vx_mps; ax_mps2 -0.0000000;-0.0440806;-0.8491629;3.4034118;0.0000525;8.0000000;0.0000000 -0.1999592;-0.2372250;-0.9009210;3.4034229;0.0000585;8.0000000;0.0000000 -0.3999183;-0.4303688;-0.9526814;3.4034352;0.0000644;8.0000000;0.0000000 -0.5998775;-0.6235119;-1.0044443;3.4034487;0.0000702;8.0000000;0.0000000 -0.7998367;-0.8166543;-1.0562099;3.4034633;0.0000759;8.0000000;0.0000000 -0.9997958;-1.0097960;-1.1079784;3.4034790;0.0000816;8.0000000;0.0000000 -1.1997550;-1.2029368;-1.1597500;3.4034959;0.0000870;8.0000000;0.0000000 -1.3997142;-1.3960767;-1.2115250;3.4035138;0.0000925;8.0000000;0.0000000 -1.5996733;-1.5892156;-1.2633036;3.4035329;0.0000978;8.0000000;0.0000000 -1.7996325;-1.7823535;-1.3150860;3.4035529;0.0001029;8.0000000;0.0000000 -1.9995916;-1.9754904;-1.3668723;3.4035740;0.0001081;8.0000000;0.0000000 -2.1995508;-2.1686261;-1.4186628;3.4035961;0.0001130;8.0000000;0.0000000 -2.3995100;-2.3617606;-1.4704577;3.4036192;0.0001179;8.0000000;0.0000000 -2.5994691;-2.5548940;-1.5222571;3.4036432;0.0001226;8.0000000;0.0000000 -2.7994283;-2.7480260;-1.5740613;3.4036682;0.0001271;8.0000000;0.0000000 -2.9993875;-2.9411568;-1.6258704;3.4036941;0.0001316;8.0000000;0.0000000 -3.1993466;-3.1342862;-1.6776845;3.4037208;0.0001358;8.0000000;0.0000000 -3.3993058;-3.3274142;-1.7295039;3.4037484;0.0001400;8.0000000;0.0000000 -3.5992650;-3.5205407;-1.7813287;3.4037768;0.0001440;8.0000000;0.0000000 -3.7992241;-3.7136658;-1.8331591;3.4038059;0.0001478;8.0000000;0.0000000 -3.9991833;-3.9067893;-1.8849951;3.4038359;0.0001515;8.0000000;0.0000000 -4.1991425;-4.0999112;-1.9368370;3.4038665;0.0001549;8.0000000;0.0000000 -4.3991016;-4.2930315;-1.9886849;3.4038978;0.0001583;8.0000000;0.0000000 -4.5990608;-4.4861502;-2.0405389;3.4039298;0.0001615;8.0000000;0.0000000 -4.7990200;-4.6792673;-2.0923992;3.4039624;0.0001645;8.0000000;0.0000000 -4.9989791;-4.8723826;-2.1442658;3.4039956;0.0001674;8.0000000;0.0000000 -5.1989383;-5.0654961;-2.1961388;3.4040293;0.0001700;8.0000000;0.0000000 -5.3988975;-5.2586080;-2.2480185;3.4040636;0.0001725;8.0000000;0.0000000 -5.5988566;-5.4517180;-2.2999048;3.4040983;0.0001748;8.0000000;0.0000000 -5.7988158;-5.6448262;-2.3517978;3.4041335;0.0001769;8.0000000;0.0000000 -5.9987749;-5.8379326;-2.4036977;3.4041691;0.0001790;8.0000000;0.0000000 -6.1987341;-6.0310371;-2.4556044;3.4042050;0.0001807;8.0000000;0.0000000 -6.3986933;-6.2241397;-2.5075182;3.4042413;0.0001823;8.0000000;0.0000000 -6.5986524;-6.4172405;-2.5594390;3.4042780;0.0001837;8.0000000;0.0000000 -6.7986116;-6.6103393;-2.6113669;3.4043148;0.0001850;8.0000000;0.0000000 -6.9985708;-6.8034362;-2.6633019;3.4043519;0.0001861;8.0000000;0.0000000 -7.1985299;-6.9965312;-2.7152441;3.4043892;0.0001869;8.0000000;0.0000000 -7.3984891;-7.1896243;-2.7671936;3.4044267;0.0001876;8.0000000;0.0000000 -7.5984483;-7.3827154;-2.8191502;3.4044642;0.0001882;8.0000000;0.0000000 -7.7984074;-7.5758045;-2.8711142;3.4045019;0.0001885;8.0000000;0.0000000 -7.9983666;-7.7688917;-2.9230854;3.4045396;0.0001887;8.0000000;0.0000000 -8.1983258;-7.9619769;-2.9750639;3.4045773;0.0001886;8.0000000;0.0000000 -8.3982849;-8.1550602;-3.0270497;3.4046150;0.0001885;8.0000000;0.0000000 -8.5982441;-8.3481415;-3.0790427;3.4046527;0.0001881;8.0000000;0.0000000 -8.7982033;-8.5412208;-3.1310431;3.4046903;0.0001875;8.0000000;0.0000000 -8.9981624;-8.7342982;-3.1830506;3.4047277;0.0001869;8.0000000;0.0000000 -9.1981216;-8.9273737;-3.2350654;3.4047650;0.0001859;8.0000000;0.0000000 -9.3980808;-9.1204472;-3.2870874;3.4048021;0.0001849;8.0000000;0.0000000 -9.5980399;-9.3135188;-3.3391165;3.4048389;0.0001837;8.0000000;0.0000000 -9.7979991;-9.5065885;-3.3911526;3.4048755;0.0001823;8.0000000;0.0000000 -9.9979582;-9.6996563;-3.4431959;3.4049118;0.0001809;8.0000000;0.0000000 -10.1979174;-9.8927222;-3.4952461;3.4049478;0.0001791;8.0000000;0.0000000 -10.3978766;-10.0857862;-3.5473032;3.4049835;0.0001773;8.0000000;0.0000000 -10.5978357;-10.2788484;-3.5993672;3.4050187;0.0001753;8.0000000;0.0000000 -10.7977949;-10.4719088;-3.6514379;3.4050535;0.0001731;8.0000000;0.0000000 -10.9977541;-10.6649673;-3.7035153;3.4050879;0.0001709;8.0000000;0.0000000 -11.1977132;-10.8580241;-3.7555993;3.4051218;0.0001683;8.0000000;0.0000000 -11.3976724;-11.0510792;-3.8076898;3.4051552;0.0001658;8.0000000;0.0000000 -11.5976316;-11.2441325;-3.8597867;3.4051881;0.0001630;8.0000000;0.0000000 -11.7975907;-11.4371841;-3.9118899;3.4052204;0.0001601;8.0000000;0.0000000 -11.9975499;-11.6302340;-3.9639993;3.4052522;0.0001572;8.0000000;0.0000000 -12.1975091;-11.8232824;-4.0161147;3.4052833;0.0001539;8.0000000;0.0000000 -12.3974682;-12.0163290;-4.0682361;3.4053137;0.0001507;8.0000000;0.0000000 -12.5974274;-12.2093742;-4.1203633;3.4053435;0.0001473;8.0000000;0.0000000 -12.7973866;-12.4024178;-4.1724962;3.4053726;0.0001437;8.0000000;0.0000000 -12.9973457;-12.5954599;-4.2246346;3.4054010;0.0001401;8.0000000;0.0000000 -13.1973049;-12.7885005;-4.2767785;3.4054286;0.0001362;8.0000000;0.0000000 -13.3972641;-12.9815397;-4.3289276;3.4054554;0.0001324;8.0000000;0.0000000 -13.5972232;-13.1745776;-4.3810818;3.4054815;0.0001284;8.0000000;0.0000000 -13.7971824;-13.3676141;-4.4332409;3.4055068;0.0001242;8.0000000;0.0000000 -13.9971415;-13.5606493;-4.4854049;3.4055312;0.0001200;8.0000000;0.0000000 -14.1971007;-13.7536832;-4.5375735;3.4055548;0.0001156;8.0000000;0.0000000 -14.3970599;-13.9467160;-4.5897465;3.4055774;0.0001112;8.0000000;0.0000000 -14.5970190;-14.1397476;-4.6419238;3.4055992;0.0001067;8.0000000;0.0000000 -14.7969782;-14.3327780;-4.6941053;3.4056201;0.0001020;8.0000000;0.0000000 -14.9969374;-14.5258074;-4.7462907;3.4056400;0.0000973;8.0000000;0.0000000 -15.1968965;-14.7188358;-4.7984799;3.4056590;0.0000924;8.0000000;0.0000000 -15.3968557;-14.9118633;-4.8506726;3.4056770;0.0000875;8.0000000;0.0000000 -15.5968149;-15.1048898;-4.9028687;3.4056940;0.0000825;8.0000000;0.0000000 -15.7967740;-15.2979154;-4.9550679;3.4057100;0.0000774;8.0000000;0.0000000 -15.9967332;-15.4909403;-5.0072702;3.4057249;0.0000722;8.0000000;0.0000000 -16.1966924;-15.6839644;-5.0594753;3.4057388;0.0000669;8.0000000;0.0000000 -16.3966515;-15.8769878;-5.1116829;3.4057517;0.0000616;8.0000000;0.0000000 -16.5966107;-16.0700105;-5.1638929;3.4057635;0.0000562;8.0000000;0.0000000 -16.7965699;-16.2630327;-5.2161051;3.4057741;0.0000506;8.0000000;0.0000000 -16.9965290;-16.4560543;-5.2683192;3.4057837;0.0000451;8.0000000;0.0000000 -17.1964882;-16.6490755;-5.3205351;3.4057922;0.0000394;8.0000000;0.0000000 -17.3964474;-16.8420962;-5.3727525;3.4057995;0.0000337;8.0000000;0.0000000 -17.5964065;-17.0351166;-5.4249712;3.4058056;0.0000279;8.0000000;0.0000000 -17.7963657;-17.2281368;-5.4771909;3.4058106;0.0000221;8.0000000;0.0000000 -17.9963248;-17.4211566;-5.5294116;3.4058145;0.0000162;8.0000000;0.0000000 -18.1962840;-17.6141764;-5.5816328;3.4058171;0.0000102;8.0000000;0.0000000 -18.3962432;-17.8071959;-5.6338544;3.4058185;0.0000041;8.0000000;0.0000000 -18.5962023;-18.0002155;-5.6860762;3.4058187;-0.0000020;8.0000000;0.0000000 -18.7961615;-18.1932351;-5.7382980;3.4058177;-0.0000081;8.0000000;0.0000000 -18.9961207;-18.3862547;-5.7905194;3.4058155;-0.0000143;8.0000000;0.0000000 -19.1960798;-18.5792746;-5.8427402;3.4058120;-0.0000206;8.0000000;0.0000000 -19.3960390;-18.7722946;-5.8949603;3.4058073;-0.0000269;8.0000000;0.0000000 -19.5959982;-18.9653149;-5.9471793;3.4058013;-0.0000333;8.0000000;0.0000000 -19.7959573;-19.1583356;-5.9993970;3.4057940;-0.0000397;8.0000000;0.0000000 -19.9959165;-19.3513566;-6.0516132;3.4057854;-0.0000462;8.0000000;0.0000000 -20.1958757;-19.5443782;-6.1038277;3.4057755;-0.0000526;8.0000000;0.0000000 -20.3958348;-19.7374003;-6.1560401;3.4057643;-0.0000590;8.0000000;0.0000000 -20.5957940;-19.9304230;-6.2082502;3.4057519;-0.0000657;8.0000000;0.0000000 -20.7957532;-20.1234465;-6.2604578;3.4057381;-0.0000725;8.0000000;0.0000000 -20.9957123;-20.3164706;-6.3126625;3.4057229;-0.0000793;8.0000000;0.0000000 -21.1956715;-20.5094956;-6.3648643;3.4057063;-0.0000860;8.0000000;0.0000000 -21.3956307;-20.7025215;-6.4170627;3.4056885;-0.0000927;8.0000000;0.0000000 -21.5955898;-20.8955483;-6.4692575;3.4056693;-0.0000990;8.0000000;0.0000000 -21.7955490;-21.0885762;-6.5214485;3.4056489;-0.0001051;8.0000000;0.0000000 -21.9955081;-21.2816052;-6.5736354;3.4056273;-0.0001108;8.0000000;0.0000000 -22.1954673;-21.4746353;-6.6258181;3.4056048;-0.0001138;8.0000000;0.0000000 -22.3954265;-21.6676667;-6.6779964;3.4055818;-0.0001167;8.0000000;0.0000000 -22.5953856;-21.8606992;-6.7301702;3.4055582;-0.0001180;8.0000000;0.0000000 -22.7953448;-22.0537330;-6.7823394;3.4055346;-0.0001181;8.0000000;0.0000000 -22.9953040;-22.2467680;-6.8345041;3.4055110;-0.0001180;8.0000000;0.0000000 -23.1952631;-22.4398042;-6.8866642;3.4054876;-0.0001155;8.0000000;0.0000000 -23.3952223;-22.6328417;-6.9388199;3.4054648;-0.0001131;8.0000000;0.0000000 -23.5951815;-22.8258803;-6.9909712;3.4054425;-0.0001091;8.0000000;0.0000000 -23.7951406;-23.0189200;-7.0431183;3.4054212;-0.0001041;8.0000000;0.0000000 -23.9950998;-23.2119609;-7.0952614;3.4054009;-0.0000989;8.0000000;0.0000000 -24.1950590;-23.4050027;-7.1474007;3.4053818;-0.0000915;8.0000000;0.0000000 -24.3950181;-23.5980455;-7.1995364;3.4053643;-0.0000842;8.0000000;0.0000000 -24.5949773;-23.7910892;-7.2516689;3.4053483;-0.0000754;8.0000000;0.0000000 -24.7949365;-23.9841337;-7.3037985;3.4053342;-0.0000656;8.0000000;0.0000000 -24.9948956;-24.1771789;-7.3559256;3.4053220;-0.0000552;8.0000000;0.0000000 -25.1948548;-24.3702246;-7.4080505;3.4053126;-0.0000389;8.0000000;0.0000000 -25.3948140;-24.5632708;-7.4601740;3.4053065;-0.0000226;8.0000000;0.0000000 -25.5947731;-24.7563171;-7.5122966;3.4053042;0.0000032;8.0000000;0.0000000 -25.7947323;-24.9493634;-7.5644193;3.4053080;0.0000352;8.0000000;0.0000000 -25.9946914;-25.1424095;-7.6165435;3.4053179;0.0000305;8.0000000;0.0000000 -26.1946506;-25.3354557;-7.6686671;3.4052921;-0.0002878;8.0000000;0.0000000 -26.3946098;-25.5285048;-7.7207797;3.4052028;-0.0006062;8.0000000;0.0000000 -26.5945689;-25.7215579;-7.7728659;3.4049954;-0.0018200;8.0000000;0.0000000 -26.7945281;-25.9146310;-7.8248816;3.4044521;-0.0036145;8.0000000;0.0000000 -26.9944873;-26.1077465;-7.8767590;3.4035492;-0.0054763;8.0000000;0.0000000 -27.1944464;-26.3009068;-7.9284187;3.4022122;-0.0078970;8.0000000;0.0000000 -27.3944056;-26.4941633;-7.9797772;3.4003912;-0.0103164;8.0000000;0.0000000 -27.5943648;-26.6875186;-8.0307333;3.3980418;-0.0134694;8.0000000;0.0000000 -27.7943239;-26.8810112;-8.0811682;3.3949863;-0.0170916;8.0000000;0.0000000 -27.9942831;-27.0746851;-8.1309440;3.3912062;-0.0207310;8.0000000;0.0000000 -28.1942423;-27.2685495;-8.1799123;3.3866831;-0.0245107;8.0000000;0.0000000 -28.3942014;-27.4626604;-8.2279320;3.3814039;-0.0282908;8.0000000;0.0000000 -28.5941606;-27.6570369;-8.2748522;3.3753719;-0.0320240;8.0000000;0.0000000 -28.7941198;-27.8517090;-8.3205266;3.3685979;-0.0357296;8.0000000;0.0000000 -28.9940789;-28.0467060;-8.3648098;3.3610827;-0.0394341;8.0000000;0.0000000 -29.1940381;-28.2420422;-8.4075534;3.3528291;-0.0431200;8.0000000;0.0000000 -29.3939973;-28.4377406;-8.4486112;3.3438379;-0.0468107;8.0000000;0.0000000 -29.5939564;-28.6338161;-8.4878359;3.3341088;-0.0504978;8.0000000;0.0000000 -29.7939156;-28.8302765;-8.5250784;3.3236423;-0.0541892;8.0000000;0.0000000 -29.9938747;-29.0271261;-8.5601894;3.3124371;-0.0578859;8.0000000;0.0000000 -30.1938339;-29.2243760;-8.5930209;3.3004927;-0.0615821;8.0000000;0.0000000 -30.3937931;-29.4220067;-8.6234196;3.2878083;-0.0652915;8.0000000;0.0000000 -30.5937522;-29.6200241;-8.6512365;3.2743813;-0.0690022;8.0000000;0.0000000 -30.7937114;-29.8184047;-8.6763184;3.2602114;-0.0727271;8.0000000;0.0000000 -30.9936706;-30.0171191;-8.6985117;3.2452957;-0.0764659;8.0000000;0.0000000 -31.1936297;-30.2161691;-8.7176659;3.2296308;-0.0802105;8.0000000;0.0000000 -31.3935889;-30.4154814;-8.7336237;3.2132159;-0.0839823;8.0000000;0.0000000 -31.5935481;-30.6150463;-8.7462330;3.1960443;-0.0877633;8.0000000;0.0000000 -31.7935072;-30.8147992;-8.7553381;3.1781145;-0.0915739;8.0000000;0.0000000 -31.9934664;-31.0146677;-8.7607837;3.1594211;-0.0954114;8.0000000;0.0000000 -32.1934256;-31.2146361;-8.7624156;3.1399570;-0.0992597;8.0000000;0.0000000 -32.3933847;-31.4145673;-8.7600786;3.1197214;-0.1031558;8.0000000;0.0000000 -32.5933439;-31.6144263;-8.7536178;3.0987023;-0.1070700;8.0000000;0.0000000 -32.7933031;-31.8140979;-8.7428797;3.0768968;-0.1110342;8.0000000;0.0000000 -32.9932622;-32.0134577;-8.7277133;3.0542958;-0.1150466;8.0000000;0.0000000 -33.1932214;-32.2124583;-8.7079607;3.0308852;-0.1190934;8.0000000;0.0000000 -33.3931805;-32.4108939;-8.6834796;3.0066621;-0.1232163;8.0000000;0.0000000 -33.5931397;-32.6086877;-8.6541140;2.9816039;-0.1274302;8.0000000;0.0000000 -33.7930989;-32.8056656;-8.6197185;2.9556913;-0.1317578;8.0000000;0.0000000 -33.9930580;-33.0016435;-8.5801511;2.9289081;-0.1361847;8.0000000;0.0000000 -34.1930172;-33.1965145;-8.5352512;2.9012102;-0.1408404;8.0000000;0.0000000 -34.3929764;-33.3900054;-8.4848914;2.8725743;-0.1456162;8.0000000;0.0000000 -34.5929355;-33.5819657;-8.4289187;2.8430647;-0.1490357;8.0000000;0.0000000 -34.7928947;-33.7721723;-8.3672515;2.8129917;-0.1517739;8.0000000;0.0000000 -34.9928539;-33.9604004;-8.2998481;2.7823784;-0.1535787;8.0000000;0.0000000 -35.1928130;-34.1464911;-8.2267195;2.7520722;-0.1495696;8.0000000;0.0000000 -35.3927722;-34.3303225;-8.1480539;2.7225572;-0.1456535;8.0000000;0.0000000 -35.5927314;-34.5117681;-8.0640782;2.6938599;-0.1411925;8.0000000;0.0000000 -35.7926905;-34.6907816;-7.9750089;2.6661015;-0.1364693;8.0000000;0.0000000 -35.9926497;-34.8673184;-7.8810771;2.6392743;-0.1318691;8.0000000;0.0000000 -36.1926089;-35.0412763;-7.7825460;2.6133524;-0.1274524;8.0000000;0.0000000 -36.3925680;-35.2127104;-7.6795878;2.5882998;-0.1231136;8.0000000;0.0000000 -36.5925272;-35.3815280;-7.5724596;2.5641106;-0.1188530;8.0000000;0.0000000 -36.7924864;-35.5477614;-7.4613438;2.5407668;-0.1146479;8.0000000;0.0000000 -36.9924455;-35.7114288;-7.3464286;2.5182532;-0.1105171;8.0000000;0.0000000 -37.1924047;-35.8724724;-7.2279576;2.4965660;-0.1064387;8.0000000;0.0000000 -37.3923638;-36.0309994;-7.1060543;2.4756836;-0.1024154;8.0000000;0.0000000 -37.5923230;-36.1869712;-6.9809506;2.4556047;-0.0984223;8.0000000;0.0000000 -37.7922822;-36.3404573;-6.8527964;2.4363218;-0.0944562;8.0000000;0.0000000 -37.9922413;-36.4915146;-6.7217493;2.4178247;-0.0905349;8.0000000;0.0000000 -38.1922005;-36.6401432;-6.5880178;2.4001146;-0.0866255;8.0000000;0.0000000 -38.3921597;-36.7864599;-6.4517070;2.3831797;-0.0827512;8.0000000;0.0000000 -38.5921188;-36.9304864;-6.3130076;2.3670184;-0.0788969;8.0000000;0.0000000 -38.7920780;-37.0723096;-6.1720510;2.3516265;-0.0750587;8.0000000;0.0000000 -38.9920372;-37.2120113;-6.0289710;2.3369982;-0.0712453;8.0000000;0.0000000 -39.1919963;-37.3496462;-5.8839307;2.3231342;-0.0674304;8.0000000;0.0000000 -39.3919555;-37.4853225;-5.7370374;2.3100303;-0.0636346;8.0000000;0.0000000 -39.5919147;-37.6191161;-5.5884326;2.2976847;-0.0598421;8.0000000;0.0000000 -39.7918738;-37.7511209;-5.4382385;2.2860977;-0.0560533;8.0000000;0.0000000 -39.9918330;-37.8814352;-5.2865729;2.2752671;-0.0522674;8.0000000;0.0000000 -40.1917922;-38.0101588;-5.1335521;2.2651982;-0.0484402;8.0000000;0.0000000 -40.3917513;-38.1373896;-4.9792971;2.2558944;-0.0446199;8.0000000;0.0000000 -40.5917105;-38.2632462;-4.8239048;2.2473589;-0.0407220;8.0000000;0.0000000 -40.7916697;-38.3878299;-4.6674970;2.2396095;-0.0367881;8.0000000;0.0000000 -40.9916288;-38.5112527;-4.5101859;2.2326447;-0.0329658;8.0000000;0.0000000 -41.1915880;-38.6336475;-4.3520460;2.2263854;-0.0296353;8.0000000;0.0000000 -41.3915471;-38.7550890;-4.1932018;2.2207930;-0.0263021;8.0000000;0.0000000 -41.5915063;-38.8756991;-4.0337139;2.2158671;-0.0229675;8.0000000;0.0000000 -41.7914655;-38.9955754;-3.8736737;2.2116083;-0.0196288;8.0000000;0.0000000 -41.9914246;-39.1148198;-3.7131680;2.2080096;-0.0167279;8.0000000;0.0000000 -42.1913838;-39.2335226;-3.5522545;2.2047526;-0.0158485;8.0000000;0.0000000 -42.3913430;-39.3517151;-3.3909652;2.2016715;-0.0149690;8.0000000;0.0000000 -42.5913021;-39.4694231;-3.2293221;2.1987319;-0.0145939;8.0000000;0.0000000 -42.7912613;-39.5866587;-3.0673361;2.1958275;-0.0144566;8.0000000;0.0000000 -42.9912205;-39.7034256;-2.9050117;2.1929505;-0.0143194;8.0000000;0.0000000 -43.1911796;-39.8197272;-2.7423538;2.1901009;-0.0141818;8.0000000;0.0000000 -43.3911388;-39.9355670;-2.5793668;2.1872789;-0.0140442;8.0000000;0.0000000 -43.5910980;-40.0509486;-2.4160553;2.1844844;-0.0139070;8.0000000;0.0000000 -43.7910571;-40.1658756;-2.2524234;2.1817172;-0.0137701;8.0000000;0.0000000 -43.9910163;-40.2803518;-2.0884755;2.1789775;-0.0136333;8.0000000;0.0000000 -44.1909755;-40.3943804;-1.9242165;2.1762650;-0.0134969;8.0000000;0.0000000 -44.3909346;-40.5079655;-1.7596500;2.1735798;-0.0133605;8.0000000;0.0000000 -44.5908938;-40.6211104;-1.5947809;2.1709219;-0.0132245;8.0000000;0.0000000 -44.7908530;-40.7338189;-1.4296131;2.1682911;-0.0130886;8.0000000;0.0000000 -44.9908121;-40.8460950;-1.2641506;2.1656875;-0.0129529;8.0000000;0.0000000 -45.1907713;-40.9579418;-1.0983985;2.1631110;-0.0128175;8.0000000;0.0000000 -45.3907304;-41.0693638;-0.9323596;2.1605616;-0.0126821;8.0000000;0.0000000 -45.5906896;-41.1803640;-0.7660391;2.1580392;-0.0125471;8.0000000;0.0000000 -45.7906488;-41.2909468;-0.5994406;2.1555438;-0.0124122;8.0000000;0.0000000 -45.9906079;-41.4011159;-0.4325677;2.1530753;-0.0122774;8.0000000;0.0000000 -46.1905671;-41.5108746;-0.2654256;2.1506338;-0.0121430;8.0000000;0.0000000 -46.3905263;-41.6202276;-0.0980168;2.1482191;-0.0120086;8.0000000;0.0000000 -46.5904854;-41.7291779;0.0696537;2.1458313;-0.0118744;8.0000000;0.0000000 -46.7904446;-41.8377299;0.2375825;2.1434703;-0.0117405;8.0000000;0.0000000 -46.9904038;-41.9458877;0.4057660;2.1411361;-0.0116066;8.0000000;0.0000000 -47.1903629;-42.0536543;0.5741994;2.1388286;-0.0114730;8.0000000;0.0000000 -47.3903221;-42.1610348;0.7428803;2.1365478;-0.0113395;8.0000000;0.0000000 -47.5902813;-42.2680321;0.9118037;2.1342937;-0.0112062;8.0000000;0.0000000 -47.7902404;-42.3746507;1.0809667;2.1320662;-0.0110731;8.0000000;0.0000000 -47.9901996;-42.4808948;1.2503657;2.1298653;-0.0109400;8.0000000;0.0000000 -48.1901588;-42.5867676;1.4199959;2.1276911;-0.0108073;8.0000000;0.0000000 -48.3901179;-42.6922740;1.5898552;2.1255433;-0.0106745;8.0000000;0.0000000 -48.5900771;-42.7974173;1.7599389;2.1234221;-0.0105420;8.0000000;0.0000000 -48.7900363;-42.9022019;1.9302439;2.1213274;-0.0104097;8.0000000;0.0000000 -48.9899954;-43.0066321;2.1007671;2.1192591;-0.0102774;8.0000000;0.0000000 -49.1899546;-43.1107111;2.2715039;2.1172172;-0.0101453;8.0000000;0.0000000 -49.3899137;-43.2144440;2.4424521;2.1152018;-0.0100133;8.0000000;0.0000000 -49.5898729;-43.3178341;2.6136072;2.1132127;-0.0098816;8.0000000;0.0000000 -49.7898321;-43.4208859;2.7849663;2.1112499;-0.0097499;8.0000000;0.0000000 -49.9897912;-43.5236037;2.9565264;2.1093135;-0.0096183;8.0000000;0.0000000 -50.1897504;-43.6259909;3.1282832;2.1074034;-0.0094869;8.0000000;0.0000000 -50.3897096;-43.7280524;3.3002343;2.1055195;-0.0093556;8.0000000;0.0000000 -50.5896687;-43.8297919;3.4723758;2.1036619;-0.0092245;8.0000000;0.0000000 -50.7896279;-43.9312138;3.6447047;2.1018305;-0.0090935;8.0000000;0.0000000 -50.9895871;-44.0323222;3.8172180;2.1000253;-0.0089625;8.0000000;0.0000000 -51.1895462;-44.1331211;3.9899119;2.0982462;-0.0088317;8.0000000;0.0000000 -51.3895054;-44.2336151;4.1627838;2.0964933;-0.0087009;8.0000000;0.0000000 -51.5894646;-44.3338080;4.3358301;2.0947665;-0.0085704;8.0000000;0.0000000 -51.7894237;-44.4337043;4.5090478;2.0930658;-0.0084401;8.0000000;0.0000000 -51.9893829;-44.5333081;4.6824341;2.0913912;-0.0083097;8.0000000;0.0000000 -52.1893421;-44.6326236;4.8559854;2.0897426;-0.0081796;8.0000000;0.0000000 -52.3893012;-44.7316552;5.0296991;2.0881200;-0.0080494;8.0000000;0.0000000 -52.5892604;-44.8304070;5.2035719;2.0865235;-0.0079194;8.0000000;0.0000000 -52.7892196;-44.9288834;5.3776008;2.0849529;-0.0077894;8.0000000;0.0000000 -52.9891787;-45.0270886;5.5517829;2.0834083;-0.0076596;8.0000000;0.0000000 -53.1891379;-45.1250269;5.7261154;2.0818897;-0.0075299;8.0000000;0.0000000 -53.3890970;-45.2227025;5.9005948;2.0803970;-0.0074002;8.0000000;0.0000000 -53.5890562;-45.3201200;6.0752189;2.0789302;-0.0072707;8.0000000;0.0000000 -53.7890154;-45.4172835;6.2499843;2.0774893;-0.0071412;8.0000000;0.0000000 -53.9889745;-45.5141971;6.4248881;2.0760743;-0.0070118;8.0000000;0.0000000 -54.1889337;-45.6108658;6.5999281;2.0746851;-0.0068825;8.0000000;0.0000000 -54.3888929;-45.7072931;6.7751003;2.0733218;-0.0067533;8.0000000;0.0000000 -54.5888520;-45.8034840;6.9504032;2.0719844;-0.0066242;8.0000000;0.0000000 -54.7888112;-45.8994426;7.1258331;2.0706727;-0.0064952;8.0000000;0.0000000 -54.9887704;-45.9951730;7.3013870;2.0693868;-0.0063663;8.0000000;0.0000000 -55.1887295;-46.0906804;7.4770636;2.0681267;-0.0062374;8.0000000;0.0000000 -55.3886887;-46.1859680;7.6528582;2.0668923;-0.0061086;8.0000000;0.0000000 -55.5886479;-46.2810413;7.8287699;2.0656837;-0.0059799;8.0000000;0.0000000 -55.7886070;-46.3759040;8.0047948;2.0645008;-0.0058513;8.0000000;0.0000000 -55.9885662;-46.4705603;8.1809299;2.0633437;-0.0057228;8.0000000;0.0000000 -56.1885254;-46.5650158;8.3571747;2.0622122;-0.0055943;8.0000000;0.0000000 -56.3884845;-46.6592732;8.5335235;2.0611064;-0.0054659;8.0000000;0.0000000 -56.5884437;-46.7533385;8.7099764;2.0600263;-0.0053376;8.0000000;0.0000000 -56.7884029;-46.8472152;8.8865292;2.0589718;-0.0052094;8.0000000;0.0000000 -56.9883620;-46.9409075;9.0631788;2.0579429;-0.0050812;8.0000000;0.0000000 -57.1883212;-47.0344212;9.2399253;2.0569397;-0.0049531;8.0000000;0.0000000 -57.3882803;-47.1277588;9.4167625;2.0559621;-0.0048250;8.0000000;0.0000000 -57.5882395;-47.2209265;9.5936911;2.0550101;-0.0046971;8.0000000;0.0000000 -57.7881987;-47.3139277;9.7707066;2.0540837;-0.0045692;8.0000000;0.0000000 -57.9881578;-47.4067666;9.9478060;2.0531828;-0.0044413;8.0000000;0.0000000 -58.1881170;-47.4994494;10.1249900;2.0523075;-0.0043135;8.0000000;0.0000000 -58.3880762;-47.5919781;10.3022515;2.0514578;-0.0041858;8.0000000;0.0000000 -58.5880353;-47.6843593;10.4795922;2.0506335;-0.0040582;8.0000000;0.0000000 -58.7879945;-47.7765963;10.6570072;2.0498348;-0.0039306;8.0000000;0.0000000 -58.9879537;-47.8686931;10.8344933;2.0490616;-0.0038031;8.0000000;0.0000000 -59.1879128;-47.9606563;11.0120521;2.0483139;-0.0036756;8.0000000;0.0000000 -59.3878720;-48.0524876;11.1896757;2.0475916;-0.0035482;8.0000000;0.0000000 -59.5878312;-48.1441939;11.3673665;2.0468949;-0.0034209;8.0000000;0.0000000 -59.7877903;-48.2357782;11.5451193;2.0462236;-0.0032937;8.0000000;0.0000000 -59.9877495;-48.3272447;11.7229309;2.0455777;-0.0031664;8.0000000;0.0000000 -60.1877087;-48.4186002;11.9008034;2.0449572;-0.0030393;8.0000000;0.0000000 -60.3876678;-48.5098460;12.0787282;2.0443622;-0.0029122;8.0000000;0.0000000 -60.5876270;-48.6009893;12.2567086;2.0437926;-0.0027852;8.0000000;0.0000000 -60.7875862;-48.6920331;12.4347389;2.0432483;-0.0026583;8.0000000;0.0000000 -60.9875453;-48.7829814;12.6128158;2.0427295;-0.0025314;8.0000000;0.0000000 -61.1875045;-48.8738413;12.7909422;2.0422360;-0.0024046;8.0000000;0.0000000 -61.3874636;-48.9646138;12.9691088;2.0417678;-0.0022778;8.0000000;0.0000000 -61.5874228;-49.0553065;13.1473194;2.0413250;-0.0021511;8.0000000;0.0000000 -61.7873820;-49.1459220;13.3255680;2.0409076;-0.0020245;8.0000000;0.0000000 -61.9873411;-49.2364644;13.5038516;2.0405154;-0.0018979;8.0000000;0.0000000 -62.1873003;-49.3269411;13.6821731;2.0401486;-0.0017714;8.0000000;0.0000000 -62.3872595;-49.4173527;13.8605229;2.0398070;-0.0016449;8.0000000;0.0000000 -62.5872186;-49.5077070;14.0389054;2.0394907;-0.0015186;8.0000000;0.0000000 -62.7871778;-49.5980067;14.2173142;2.0391997;-0.0013923;8.0000000;0.0000000 -62.9871370;-49.6882558;14.3957463;2.0389339;-0.0012660;8.0000000;0.0000000 -63.1870961;-49.7784616;14.5742051;2.0386934;-0.0011399;8.0000000;0.0000000 -63.3870553;-49.8686248;14.7526805;2.0384781;-0.0010137;8.0000000;0.0000000 -63.5870145;-49.9587533;14.9311772;2.0382880;-0.0008877;8.0000000;0.0000000 -63.7869736;-50.0488496;15.1096889;2.0381230;-0.0007617;8.0000000;0.0000000 -63.9869328;-50.1389177;15.2882123;2.0379833;-0.0006358;8.0000000;0.0000000 -64.1868920;-50.2289652;15.4667512;2.0378688;-0.0005100;8.0000000;0.0000000 -64.3868511;-50.3189923;15.6452951;2.0377794;-0.0003842;8.0000000;0.0000000 -64.5868103;-50.4090074;15.8238491;2.0377151;-0.0002586;8.0000000;0.0000000 -64.7867695;-50.4990126;16.0024066;2.0376759;-0.0001332;8.0000000;0.0000000 -64.9867286;-50.5890121;16.1809647;2.0376618;-0.0000081;8.0000000;0.0000000 -65.1866878;-50.6790134;16.3595269;2.0376726;0.0001158;8.0000000;0.0000000 -65.3866469;-50.7690167;16.5380828;2.0377081;0.0002397;8.0000000;0.0000000 -65.5866061;-50.8590301;16.7166377;2.0377682;0.0003598;8.0000000;0.0000000 -65.7865653;-50.9490558;16.8951848;2.0378520;0.0004785;8.0000000;0.0000000 -65.9865244;-51.0390975;17.0737213;2.0379598;0.0006072;8.0000000;0.0000000 -66.1864836;-51.1291629;17.2522504;2.0380976;0.0007711;8.0000000;0.0000000 -66.3864428;-51.2192542;17.4307624;2.0382682;0.0009351;8.0000000;0.0000000 -66.5864019;-51.3093801;17.6092600;2.0384715;0.0010980;8.0000000;0.0000000 -66.7863611;-51.3995447;17.7877370;2.0387073;0.0012605;8.0000000;0.0000000 -66.9863203;-51.4897537;17.9661900;2.0389755;0.0014204;8.0000000;0.0000000 -67.1862794;-51.5800148;18.1446203;2.0392746;0.0015709;8.0000000;0.0000000 -67.3862386;-51.6703304;18.3230190;2.0396038;0.0017215;8.0000000;0.0000000 -67.5861978;-51.7607086;18.5013892;2.0399631;0.0018719;8.0000000;0.0000000 -67.7861569;-51.8511531;18.6797245;2.0403524;0.0020223;8.0000000;0.0000000 -67.9861161;-51.9416690;18.8580219;2.0407718;0.0021725;8.0000000;0.0000000 -68.1860753;-52.0322638;19.0362828;2.0412212;0.0023227;8.0000000;0.0000000 -68.3860344;-52.1229398;19.2144986;2.0417007;0.0024728;8.0000000;0.0000000 -68.5859936;-52.2137053;19.3926720;2.0422101;0.0026228;8.0000000;0.0000000 -68.7859527;-52.3045636;19.5707968;2.0427496;0.0027727;8.0000000;0.0000000 -68.9859119;-52.3955201;19.7488699;2.0433190;0.0029225;8.0000000;0.0000000 -69.1858711;-52.4865819;19.9268926;2.0439183;0.0030722;8.0000000;0.0000000 -69.3858302;-52.5777517;20.1048564;2.0445476;0.0032219;8.0000000;0.0000000 -69.5857894;-52.6690373;20.2827637;2.0452068;0.0033715;8.0000000;0.0000000 -69.7857486;-52.7604423;20.4606086;2.0458959;0.0035210;8.0000000;0.0000000 -69.9857077;-52.8519719;20.6383880;2.0466149;0.0036704;8.0000000;0.0000000 -70.1856669;-52.9436333;20.8161025;2.0473638;0.0038197;8.0000000;0.0000000 -70.3856261;-53.0354290;20.9937444;2.0481425;0.0039690;8.0000000;0.0000000 -70.5855852;-53.1273667;21.1713155;2.0489511;0.0041182;8.0000000;0.0000000 -70.7855444;-53.2194502;21.3488100;2.0497894;0.0042673;8.0000000;0.0000000 -70.9855036;-53.3116847;21.5262249;2.0506576;0.0044163;8.0000000;0.0000000 -71.1854627;-53.4040768;21.7035603;2.0515556;0.0045652;8.0000000;0.0000000 -71.3854219;-53.4966297;21.8808091;2.0524833;0.0047141;8.0000000;0.0000000 -71.5853811;-53.5893505;22.0579725;2.0534408;0.0048628;8.0000000;0.0000000 -71.7853402;-53.6822432;22.2350448;2.0544281;0.0050115;8.0000000;0.0000000 -71.9852994;-53.7753128;22.4120232;2.0554450;0.0051601;8.0000000;0.0000000 -72.1852586;-53.8685659;22.5889072;2.0564917;0.0053086;8.0000000;0.0000000 -72.3852177;-53.9620057;22.7656901;2.0575680;0.0054571;8.0000000;0.0000000 -72.5851769;-54.0556393;22.9423727;2.0586741;0.0056055;8.0000000;0.0000000 -72.7851360;-54.1494704;23.1189495;2.0598098;0.0057538;8.0000000;0.0000000 -72.9850952;-54.2435043;23.2954176;2.0609751;0.0059021;8.0000000;0.0000000 -73.1850544;-54.3377472;23.4717760;2.0621701;0.0060502;8.0000000;0.0000000 -73.3850135;-54.4322025;23.6480186;2.0633947;0.0061983;8.0000000;0.0000000 -73.5849727;-54.5268769;23.8241455;2.0646489;0.0063463;8.0000000;0.0000000 -73.7849319;-54.6217744;24.0001515;2.0659327;0.0064942;8.0000000;0.0000000 -73.9848910;-54.7169001;24.1760336;2.0672460;0.0066421;8.0000000;0.0000000 -74.1848502;-54.8122600;24.3517904;2.0685890;0.0067899;8.0000000;0.0000000 -74.3848094;-54.9078577;24.5274162;2.0699614;0.0069376;8.0000000;0.0000000 -74.5847685;-55.0036995;24.7029104;2.0713634;0.0070853;8.0000000;0.0000000 -74.7847277;-55.0997896;24.8782681;2.0727950;0.0072328;8.0000000;0.0000000 -74.9846869;-55.1961330;25.0534863;2.0742560;0.0073804;8.0000000;0.0000000 -75.1846460;-55.2927354;25.2285630;2.0757465;0.0075278;8.0000000;0.0000000 -75.3846052;-55.3896007;25.4034931;2.0772665;0.0076752;8.0000000;0.0000000 -75.5845644;-55.4867348;25.5782751;2.0788160;0.0078225;8.0000000;0.0000000 -75.7845235;-55.5841419;25.7529047;2.0803949;0.0079698;8.0000000;0.0000000 -75.9844827;-55.6818271;25.9273786;2.0820032;0.0081170;8.0000000;0.0000000 -76.1844419;-55.7797957;26.1016942;2.0836410;0.0082641;8.0000000;0.0000000 -76.3844010;-55.8780518;26.2758471;2.0853082;0.0084113;8.0000000;0.0000000 -76.5843602;-55.9766010;26.4498350;2.0870048;0.0085582;8.0000000;0.0000000 -76.7843193;-56.0754477;26.6236538;2.0887308;0.0087052;8.0000000;0.0000000 -76.9842785;-56.1745967;26.7973002;2.0904862;0.0088522;8.0000000;0.0000000 -77.1842377;-56.2740531;26.9707710;2.0922709;0.0089990;8.0000000;0.0000000 -77.3841968;-56.3738213;27.1440624;2.0940851;0.0091458;8.0000000;0.0000000 -77.5841560;-56.4739064;27.3171712;2.0959285;0.0092926;8.0000000;0.0000000 -77.7841152;-56.5743129;27.4900936;2.0978013;0.0094393;8.0000000;0.0000000 -77.9840743;-56.6750456;27.6628262;2.0997035;0.0095860;8.0000000;0.0000000 -78.1840335;-56.7761093;27.8353654;2.1016349;0.0097326;8.0000000;0.0000000 -78.3839927;-56.8775085;28.0077077;2.1035957;0.0098792;8.0000000;0.0000000 -78.5839518;-56.9792480;28.1798492;2.1055858;0.0100258;8.0000000;0.0000000 -78.7839110;-57.0813324;28.3517864;2.1076052;0.0101723;8.0000000;0.0000000 -78.9838702;-57.1837663;28.5235157;2.1096539;0.0103188;8.0000000;0.0000000 -79.1838293;-57.2865542;28.6950332;2.1117319;0.0104652;8.0000000;0.0000000 -79.3837885;-57.3897011;28.8663354;2.1138391;0.0106117;8.0000000;0.0000000 -79.5837477;-57.4932109;29.0374180;2.1159757;0.0107581;8.0000000;0.0000000 -79.7837068;-57.5970887;29.2082778;2.1181415;0.0109045;8.0000000;0.0000000 -79.9836660;-57.7013388;29.3789108;2.1203366;0.0110509;8.0000000;0.0000000 -80.1836252;-57.8059655;29.5493126;2.1225609;0.0111972;8.0000000;0.0000000 -80.3835843;-57.9109739;29.7194803;2.1248146;0.0113436;8.0000000;0.0000000 -80.5835435;-58.0163675;29.8894088;2.1270974;0.0114900;8.0000000;0.0000000 -80.7835026;-58.1221515;30.0590950;2.1294096;0.0116363;8.0000000;0.0000000 -80.9834618;-58.2283301;30.2285347;2.1317510;0.0117827;8.0000000;0.0000000 -81.1834210;-58.3349073;30.3977233;2.1341217;0.0119291;8.0000000;0.0000000 -81.3833801;-58.4418883;30.5666580;2.1365217;0.0120755;8.0000000;0.0000000 -81.5833393;-58.5492763;30.7353330;2.1389510;0.0122219;8.0000000;0.0000000 -81.7832985;-58.6570766;30.9037455;2.1414095;0.0123684;8.0000000;0.0000000 -81.9832576;-58.7652931;31.0718911;2.1438973;0.0125149;8.0000000;0.0000000 -82.1832168;-58.8739296;31.2397647;2.1464144;0.0126615;8.0000000;0.0000000 -82.3831760;-58.9829915;31.4073637;2.1489609;0.0128081;8.0000000;0.0000000 -82.5831351;-59.0924815;31.5746817;2.1515366;0.0129547;8.0000000;0.0000000 -82.7830943;-59.2024050;31.7417162;2.1541417;0.0131015;8.0000000;0.0000000 -82.9830535;-59.3127658;31.9084623;2.1567761;0.0132483;8.0000000;0.0000000 -83.1830126;-59.4235674;32.0749147;2.1594399;0.0133951;8.0000000;0.0000000 -83.3829718;-59.5348153;32.2410709;2.1621331;0.0135421;8.0000000;0.0000000 -83.5829310;-59.6465118;32.4069239;2.1648557;0.0136892;8.0000000;0.0000000 -83.7828901;-59.7586624;32.5724713;2.1676077;0.0138364;8.0000000;0.0000000 -83.9828493;-59.8712707;32.7377080;2.1703891;0.0139837;8.0000000;0.0000000 -84.1828085;-59.9843400;32.9026283;2.1732000;0.0141311;8.0000000;0.0000000 -84.3827676;-60.0978758;33.0672298;2.1760404;0.0142786;8.0000000;0.0000000 -84.5827268;-60.2118800;33.2315049;2.1789103;0.0144264;8.0000000;0.0000000 -84.7826859;-60.3263583;33.3954514;2.1818098;0.0145744;8.0000000;0.0000000 -84.9826451;-60.4413139;33.5590637;2.1847389;0.0147229;8.0000000;0.0000000 -85.1826043;-60.5567501;33.7223360;2.1876978;0.0148723;8.0000000;0.0000000 -85.3825634;-60.6726724;33.8852657;2.1906866;0.0150218;8.0000000;0.0000000 -85.5825226;-60.7890824;34.0478448;2.1937054;0.0151728;8.0000000;0.0000000 -85.7824818;-60.9059857;34.2100710;2.1967545;0.0153242;8.0000000;0.0000000 -85.9824409;-61.0233857;34.3719382;2.1998339;0.0154762;8.0000000;0.0000000 -86.1824001;-61.1412855;34.5334406;2.2029438;0.0156294;8.0000000;0.0000000 -86.3823593;-61.2596904;34.6945752;2.2060843;0.0157826;8.0000000;0.0000000 -86.5823184;-61.3786021;34.8553336;2.2092557;0.0159373;8.0000000;0.0000000 -86.7822776;-61.4980262;35.0157132;2.2124580;0.0160923;8.0000000;0.0000000 -86.9822368;-61.6179658;35.1757077;2.2156913;0.0162479;8.0000000;0.0000000 -87.1821959;-61.7384240;35.3353110;2.2189559;0.0164046;8.0000000;0.0000000 -87.3821551;-61.8594061;35.4945196;2.2222518;0.0165614;8.0000000;0.0000000 -87.5821143;-61.9809135;35.6533252;2.2255792;0.0167194;8.0000000;0.0000000 -87.7820734;-62.1029520;35.8117245;2.2289382;0.0168778;8.0000000;0.0000000 -87.9820326;-62.2255243;35.9697111;2.2323289;0.0170369;8.0000000;0.0000000 -88.1819918;-62.3486336;36.1272787;2.2357516;0.0171970;8.0000000;0.0000000 -88.3819509;-62.4722849;36.2844230;2.2392064;0.0173574;8.0000000;0.0000000 -88.5819101;-62.5964799;36.4411359;2.2426932;0.0175180;8.0000000;0.0000000 -88.7818692;-62.7212236;36.5974136;2.2462121;0.0176788;8.0000000;0.0000000 -88.9818284;-62.8465190;36.7532494;2.2497636;0.0178493;8.0000000;0.0000000 -89.1817876;-62.9723695;36.9086365;2.2533513;0.0180345;8.0000000;0.0000000 -89.3817467;-63.0987802;37.0635695;2.2569760;0.0182202;8.0000000;0.0000000 -89.5817059;-63.2257535;37.2180400;2.2606358;0.0183834;8.0000000;0.0000000 -89.7816651;-63.3532943;37.3720433;2.2643278;0.0185442;8.0000000;0.0000000 -89.9816242;-63.4814048;37.5255723;2.2680445;0.0185194;8.0000000;0.0000000 -90.1815834;-63.6100819;37.6786258;2.2717178;0.0182212;8.0000000;0.0000000 -90.3815426;-63.7393179;37.8312116;2.2753315;0.0179230;8.0000000;0.0000000 -90.5815017;-63.8690970;37.9833307;2.2788795;0.0175583;8.0000000;0.0000000 -90.7814609;-63.9994111;38.1349951;2.2823533;0.0171872;8.0000000;0.0000000 -90.9814201;-64.1302458;38.2862109;2.2857531;0.0168189;8.0000000;0.0000000 -91.1813792;-64.2615873;38.4369847;2.2890797;0.0164541;8.0000000;0.0000000 -91.3813384;-64.3934257;38.5873273;2.2923334;0.0160894;8.0000000;0.0000000 -91.5812976;-64.5257452;38.7372428;2.2955142;0.0157249;8.0000000;0.0000000 -91.7812567;-64.6585366;38.8867428;2.2986221;0.0153605;8.0000000;0.0000000 -91.9812159;-64.7917865;39.0358341;2.3016571;0.0149964;8.0000000;0.0000000 -92.1811751;-64.9254822;39.1845246;2.3046194;0.0146328;8.0000000;0.0000000 -92.3811342;-65.0596137;39.3328245;2.3075091;0.0142693;8.0000000;0.0000000 -92.5810934;-65.1941663;39.4807396;2.3103261;0.0139066;8.0000000;0.0000000 -92.7810525;-65.3291305;39.6282808;2.3130706;0.0135441;8.0000000;0.0000000 -92.9810117;-65.4644937;39.7754559;2.3157426;0.0131819;8.0000000;0.0000000 -93.1809709;-65.6002440;39.9222732;2.3183423;0.0128201;8.0000000;0.0000000 -93.3809300;-65.7363712;40.0687431;2.3208696;0.0124584;8.0000000;0.0000000 -93.5808892;-65.8728616;40.2148720;2.3233247;0.0120973;8.0000000;0.0000000 -93.7808484;-66.0097058;40.3606712;2.3257076;0.0117363;8.0000000;0.0000000 -93.9808075;-66.1468918;40.5061488;2.3280183;0.0113756;8.0000000;0.0000000 -94.1807667;-66.2844078;40.6513135;2.3302569;0.0110153;8.0000000;0.0000000 -94.3807259;-66.4222444;40.7961760;2.3324235;0.0106551;8.0000000;0.0000000 -94.5806850;-66.5603878;40.9407431;2.3345181;0.0102953;8.0000000;0.0000000 -94.7806442;-66.6988295;41.0850264;2.3365408;0.0099357;8.0000000;0.0000000 -94.9806034;-66.8375574;41.2290343;2.3384916;0.0095763;8.0000000;0.0000000 -95.1805625;-66.9765604;41.3727758;2.3403706;0.0092173;8.0000000;0.0000000 -95.3805217;-67.1158292;41.5162620;2.3421778;0.0088583;8.0000000;0.0000000 -95.5804809;-67.2553504;41.6594997;2.3439132;0.0084999;8.0000000;0.0000000 -95.7804400;-67.3951159;41.8025011;2.3455771;0.0081415;8.0000000;0.0000000 -95.9803992;-67.5351138;41.9452746;2.3471692;0.0077833;8.0000000;0.0000000 -96.1803584;-67.6753333;42.0878296;2.3486897;0.0074252;8.0000000;0.0000000 -96.3803175;-67.8157656;42.2301776;2.3501387;0.0070671;8.0000000;0.0000000 -96.5802767;-67.9563971;42.3723251;2.3515161;0.0067098;8.0000000;0.0000000 -96.7802358;-68.0972204;42.5142850;2.3528220;0.0063525;8.0000000;0.0000000 -96.9801950;-68.2382237;42.6560658;2.3540566;0.0059956;8.0000000;0.0000000 -97.1801542;-68.3793963;42.7976768;2.3552198;0.0056392;8.0000000;0.0000000 -97.3801133;-68.5207301;42.9391301;2.3563118;0.0052828;8.0000000;0.0000000 -97.5800725;-68.6622110;43.0804319;2.3573325;0.0049271;8.0000000;0.0000000 -97.7800317;-68.8038325;43.2215956;2.3582822;0.0045714;8.0000000;0.0000000 -97.9799908;-68.9455828;43.3626296;2.3591608;0.0042162;8.0000000;0.0000000 -98.1799500;-69.0874513;43.5035434;2.3599684;0.0038615;8.0000000;0.0000000 -98.3799092;-69.2294302;43.6443493;2.3607050;0.0035068;8.0000000;0.0000000 -98.5798683;-69.3715056;43.7850533;2.3613709;0.0031532;8.0000000;0.0000000 -98.7798275;-69.5136711;43.9256692;2.3619660;0.0027996;8.0000000;0.0000000 -98.9797867;-69.6559150;44.0662052;2.3624905;0.0024466;8.0000000;0.0000000 -99.1797458;-69.7982271;44.2066711;2.3629445;0.0020943;8.0000000;0.0000000 -99.3797050;-69.9405998;44.3470790;2.3633281;0.0017420;8.0000000;0.0000000 -99.5796642;-70.0830189;44.4874349;2.3636413;0.0013912;8.0000000;0.0000000 -99.7796233;-70.2254786;44.6277528;2.3638845;0.0010405;8.0000000;0.0000000 -99.9795825;-70.3679673;44.7680407;2.3640575;0.0006907;8.0000000;0.0000000 -100.1795416;-70.5104747;44.9083084;2.3641608;0.0003420;8.0000000;0.0000000 -100.3795008;-70.6529935;45.0485680;2.3641943;-0.0000068;8.0000000;0.0000000 -100.5794600;-70.7955096;45.1888255;2.3641583;-0.0003533;8.0000000;0.0000000 -100.7794191;-70.9380174;45.3290945;2.3640530;-0.0006998;8.0000000;0.0000000 -100.9793783;-71.0805054;45.4693832;2.3638785;-0.0010444;8.0000000;0.0000000 -101.1793375;-71.2229634;45.6097011;2.3636354;-0.0013869;8.0000000;0.0000000 -101.3792966;-71.3653842;45.7500601;2.3633239;-0.0017294;8.0000000;-2.9592827 -101.5792558;-71.5077541;45.8904662;2.3629441;-0.0020691;7.9256879;-5.4249199 -101.7792150;-71.6500674;46.0309325;2.3624964;-0.0024087;7.7876186;-5.4254150 -101.9791741;-71.7923129;46.1714671;2.3619812;-0.0027395;7.6470439;-5.4291430 -102.1791333;-71.9344809;46.3120792;2.3614013;-0.0030604;7.5037369;-5.4362009 -102.3790925;-72.0765640;46.4527794;2.3607573;-0.0033813;7.3574473;-5.4460851 -102.5790516;-72.2185500;46.5935739;2.3600478;-0.0037154;7.2079152;-5.4582110 -102.7790108;-72.3604326;46.7344750;2.3592715;-0.0040498;7.0548709;-5.4226721 -102.9789700;-72.5021983;46.8754913;2.3583597;-0.0058347;6.8994621;-5.3067057 -103.1789291;-72.6437967;47.0166744;2.3568526;-0.0092394;6.7439104;-5.2060120 -103.3788883;-72.7851387;47.1581236;2.3546648;-0.0126430;6.5877423;-4.7303460 -103.5788475;-72.9260704;47.2999603;2.3508928;-0.0253269;6.4425613;-4.2852183 -103.7788066;-73.0662905;47.4425175;2.3445360;-0.0382520;6.3081581;-3.9283141 -103.9787658;-73.2054188;47.5861429;2.3356601;-0.0498142;6.1823826;-3.6546721 -104.1787249;-73.3431092;47.7311426;2.3246911;-0.0599015;6.0630260;-3.4021669 -104.3786841;-73.4790551;47.8777837;2.3117028;-0.0700079;5.9497643;-3.1711278 -104.5786433;-73.6129609;48.0263419;2.2966977;-0.0800560;5.8422173;-2.9536777 -104.7786024;-73.7444378;48.1769867;2.2796773;-0.0902066;5.7402328;-2.7458639 -104.9785616;-73.8732052;48.3300140;2.2606095;-0.1005221;5.6437710;-2.5432098 -105.1785208;-73.9988785;48.4856108;2.2394507;-0.1110859;5.5529339;-2.3458982 -105.3784799;-74.1209535;48.6438158;2.2161809;-0.1218371;5.4678065;-2.1686166 -105.5784391;-74.2393340;48.8052108;2.1907573;-0.1322381;5.3879159;-1.9901160 -105.7783983;-74.3532541;48.9694650;2.1632598;-0.1429240;5.3135444;-1.8136368 -105.9783574;-74.4624855;49.1369870;2.1335926;-0.1537194;5.2448496;-1.6335473 -106.1783166;-74.5665469;49.3078422;2.1017439;-0.1647435;5.1821967;-1.4438580 -106.3782758;-74.6647424;49.4817060;2.0677159;-0.1761171;5.1261815;-1.2535121 -106.5782349;-74.7570216;49.6594298;2.0313235;-0.1874099;5.0770498;-1.0456145 -106.7781941;-74.8423908;49.8401014;1.9927085;-0.1991156;5.0356999;-0.8151303 -106.9781533;-74.9205535;50.0241499;1.9516880;-0.2112501;5.0032278;-0.5990283 -107.1781124;-74.9908872;50.2113790;1.9081734;-0.2239246;4.9792295;-0.5932956 -107.3780716;-75.0526811;50.4012856;1.8621578;-0.2369512;4.9553462;-0.5876176 -107.5780308;-75.1055071;50.5942659;1.8133534;-0.2509274;4.9315776;-0.5819941 -107.7779899;-75.1485341;50.7894172;1.7617803;-0.2651816;4.9079229;-0.5764243 -107.9779491;-75.1811524;50.9865213;1.7073022;-0.2804877;4.8843817;-0.5709078 -108.1779082;-75.2026856;51.1852274;1.6496597;-0.2961493;4.8609534;-0.5654442 -108.3778674;-75.2124269;51.3848613;1.5889153;-0.3130538;4.8376375;-0.5600328 -108.5778266;-75.2096576;51.5842192;1.5241135;-0.3366211;4.8144334;-0.5546732 -108.7777857;-75.1934172;51.7839081;1.4544635;-0.3580153;4.7913406;-0.5493649 -108.9777449;-75.1630513;51.9809958;1.3803425;-0.3883001;4.7683586;-0.5441074 -109.1777041;-75.1173737;52.1756448;1.2990208;-0.4253655;4.7454869;-0.5389002 -109.3776632;-75.0551592;52.3661480;1.2102984;-0.4480127;4.7227248;-0.5337429 -109.5776224;-74.9766536;52.5495428;1.1230336;-0.4277556;4.7000719;-0.5286349 -109.7775816;-74.8823336;52.7263196;1.0387397;-0.4146156;4.6775277;-0.5235758 -109.9775407;-74.7739223;52.8943421;0.9576209;-0.3928545;4.6550916;-0.5185651 -110.1774999;-74.6526762;53.0533038;0.8815903;-0.3680928;4.6327631;-0.5136023 -110.3774591;-74.5199514;53.2030236;0.8101139;-0.3466218;4.6105417;-0.5086871 -110.5774182;-74.3772762;53.3430868;0.7428993;-0.3258394;4.5884269;-0.5038189 -110.7773774;-74.2257808;53.4735580;0.6796826;-0.3067736;4.5664182;-0.4989973 -110.9773366;-74.0665043;53.5945377;0.6200928;-0.2889202;4.5445150;-0.4989973 -111.1772957;-73.9005408;53.7060904;0.5640714;-0.2714597;4.5225058;-0.3076088 -111.3772549;-73.7288972;53.8083965;0.5114738;-0.2551324;4.5088846;0.0675019 -111.5772141;-73.5519891;53.9019575;0.4620054;-0.2392284;4.5118772;0.3822245 -111.7771732;-73.3710405;53.9868390;0.4157438;-0.2237460;4.5287851;0.6510527 -111.9771324;-73.1863854;54.0635792;0.3724915;-0.2089094;4.5574403;0.8803363 -112.1770915;-72.9986412;54.1325557;0.3321722;-0.1942466;4.5959030;1.0887619 -112.3770507;-72.8086358;54.1941024;0.2948194;-0.1798269;4.6430314;1.2809559 -112.5770099;-72.6161233;54.2488974;0.2602537;-0.1655151;4.6978738;1.4648986 -112.7769690;-72.4221693;54.2972233;0.2286027;-0.1511700;4.7598170;1.6478077 -112.9769282;-72.2268054;54.3396755;0.1998345;-0.1363197;4.8285450;1.8441351 -113.1768874;-72.0302695;54.3768052;0.1741258;-0.1207243;4.9043195;2.0629975 -113.3768465;-71.8331116;54.4091459;0.1515683;-0.1050746;4.9877230;2.2910841 -113.5768057;-71.6350416;54.4373812;0.1321726;-0.0887596;5.0787427;2.5479853 -113.7767649;-71.4366558;54.4620772;0.1160710;-0.0723066;5.1780897;2.8243942 -113.9767240;-71.2379284;54.4838999;0.1031370;-0.0586206;5.2860326;3.0438751 -114.1766832;-71.0388993;54.5033911;0.0924485;-0.0482623;5.3999483;3.1881908 -114.3766424;-70.8397827;54.5209530;0.0838411;-0.0378521;5.5167434;3.3542803 -114.5766015;-70.6404417;54.5369594;0.0764344;-0.0366614;5.6370112;3.2487928 -114.7765607;-70.4410240;54.5515014;0.0691777;-0.0359224;5.7510997;3.1371688 -114.9765199;-70.2415092;54.5646114;0.0620927;-0.0346721;5.8591603;3.0506776 -115.1764790;-70.0418932;54.5763399;0.0553455;-0.0328123;5.9623637;2.9934135 -115.3764382;-69.8422108;54.5867582;0.0489706;-0.0309514;6.0619223;2.9438120 -115.5763974;-69.6424596;54.5959397;0.0429485;-0.0292907;6.1582616;2.8937406 -115.7763565;-69.4426619;54.6039509;0.0372565;-0.0276417;6.2515155;2.8497005 -115.9763157;-69.2428221;54.6108576;0.0318932;-0.0260113;6.3420102;2.8109920 -116.1762748;-69.0429474;54.6167249;0.0268530;-0.0244013;6.4300280;2.7771467 -116.3762340;-68.8430528;54.6216167;0.0221348;-0.0227913;6.5158186;2.7486686 -116.5761932;-68.6431297;54.6255963;0.0177175;-0.0213993;6.5996315;2.7157779 -116.7761523;-68.4431962;54.6287204;0.0135767;-0.0200180;6.6814089;2.6870692 -116.9761115;-68.2432516;54.6310436;0.0096967;-0.0189739;6.7613485;2.6473568 -117.1760707;-68.0432977;54.6326075;0.0059666;-0.0183343;6.8391929;2.5926836 -117.3760298;-67.8433432;54.6334383;0.0023645;-0.0176944;6.9145803;2.5415203 -117.5759890;-67.6433834;54.6335595;6.2820427;-0.0173994;6.9876907;2.4768275 -117.7759482;-67.4434256;54.6329851;6.2785914;-0.0171203;7.0582116;2.4143052 -117.9759073;-67.2434712;54.6317260;6.2751927;-0.0169127;7.1262806;2.3509534 -118.1758665;-67.0435216;54.6297905;6.2718231;-0.0167906;7.1919444;2.2858204 -118.3758257;-66.8435792;54.6271838;6.2684778;-0.0166686;7.2552192;2.2231671 -118.5757848;-66.6436469;54.6239107;6.2651589;-0.0165260;7.3162348;2.1639959 -118.7757440;-66.4437265;54.6199770;6.2618688;-0.0163827;7.3751416;2.1071242 -118.9757032;-66.2438198;54.6153884;6.2586073;-0.0162369;7.4320516;2.0525545 -119.1756623;-66.0439291;54.6101508;6.2553755;-0.0160880;7.4870719;2.0002289 -119.3756215;-65.8440570;54.6042702;6.2521734;-0.0159393;7.5403033;1.9498716 -119.5755807;-65.6442039;54.5977526;6.2490010;-0.0157914;7.5918353;1.9013628 -119.7755398;-65.4443728;54.5906039;6.2458581;-0.0156435;7.6417506;1.8546588 -119.9754990;-65.2445649;54.5828303;6.2427449;-0.0154945;7.6901277;1.8097607 -120.1754581;-65.0447819;54.5744375;6.2396617;-0.0153441;7.7370421;1.7666064 -120.3754173;-64.8450259;54.5654319;6.2366085;-0.0151938;7.7825651;1.7250340 -120.5753765;-64.6452977;54.5558194;6.2335855;-0.0150423;7.8267613;1.6850691 -120.7753356;-64.4455997;54.5456062;6.2305928;-0.0148908;7.8696939;1.6465643 -120.9752948;-64.2459330;54.5347985;6.2276304;-0.0147387;7.9114204;1.6095076 -121.1752540;-64.0462988;54.5234023;6.2246986;-0.0145857;7.9519963;1.5738536 -121.3752131;-63.8466990;54.5114240;6.2217973;-0.0144329;7.9914741;0.3409253 -121.5751723;-63.6471342;54.4988696;6.2189268;-0.0142787;8.0000000;0.0000000 -121.7751315;-63.4476063;54.4857456;6.2160870;-0.0141246;8.0000000;0.0000000 -121.9750906;-63.2481162;54.4720580;6.2132781;-0.0139700;8.0000000;0.0000000 -122.1750498;-63.0486650;54.4578133;6.2105002;-0.0138146;8.0000000;0.0000000 -122.3750090;-62.8492544;54.4430176;6.2077533;-0.0136594;8.0000000;0.0000000 -122.5749681;-62.6498842;54.4276774;6.2050377;-0.0135029;8.0000000;0.0000000 -122.7749273;-62.4505567;54.4117989;6.2023533;-0.0133465;8.0000000;0.0000000 -122.9748865;-62.2512721;54.3953885;6.1997002;-0.0131895;8.0000000;0.0000000 -123.1748456;-62.0520313;54.3784525;6.1970786;-0.0130318;8.0000000;0.0000000 -123.3748048;-61.8528359;54.3609975;6.1944885;-0.0128742;8.0000000;0.0000000 -123.5747640;-61.6536853;54.3430297;6.1919301;-0.0127154;8.0000000;0.0000000 -123.7747231;-61.4545815;54.3245557;6.1894034;-0.0125566;8.0000000;0.0000000 -123.9746823;-61.2555247;54.3055817;6.1869085;-0.0123972;8.0000000;0.0000000 -124.1746414;-61.0565152;54.2861144;6.1844456;-0.0122371;8.0000000;0.0000000 -124.3746006;-60.8575547;54.2661603;6.1820147;-0.0120771;8.0000000;0.0000000 -124.5745598;-60.6586420;54.2457256;6.1796159;-0.0119157;8.0000000;0.0000000 -124.7745189;-60.4597792;54.2248171;6.1772494;-0.0117544;8.0000000;0.0000000 -124.9744781;-60.2609659;54.2034413;6.1749151;-0.0115924;8.0000000;0.0000000 -125.1744373;-60.0622025;54.1816046;6.1726134;-0.0114297;8.0000000;0.0000000 -125.3743964;-59.8634902;54.1593138;6.1703442;-0.0112671;8.0000000;0.0000000 -125.5743556;-59.6648276;54.1365753;6.1681076;-0.0111030;8.0000000;0.0000000 -125.7743148;-59.4662167;54.1133958;6.1659039;-0.0109389;8.0000000;0.0000000 -125.9742739;-59.2676568;54.0897820;6.1637330;-0.0107741;8.0000000;0.0000000 -126.1742331;-59.0691480;54.0657404;6.1615951;-0.0106085;8.0000000;0.0000000 -126.3741923;-58.8706915;54.0412779;6.1594904;-0.0104430;8.0000000;0.0000000 -126.5741514;-58.6722852;54.0164008;6.1574190;-0.0102757;8.0000000;0.0000000 -126.7741106;-58.4739313;53.9911163;6.1553810;-0.0101084;8.0000000;0.0000000 -126.9740698;-58.2756288;53.9654309;6.1533765;-0.0099406;8.0000000;0.0000000 -127.1740289;-58.0773775;53.9393513;6.1514056;-0.0097721;8.0000000;0.0000000 -127.3739881;-57.8791782;53.9128845;6.1494685;-0.0096036;8.0000000;0.0000000 -127.5739473;-57.6810290;53.8860370;6.1475650;-0.0094352;8.0000000;0.0000000 -127.7739064;-57.4829316;53.8588157;6.1456951;-0.0092668;8.0000000;0.0000000 -127.9738656;-57.2848847;53.8312275;6.1438590;-0.0090987;8.0000000;0.0000000 -128.1738247;-57.0868882;53.8032789;6.1420564;-0.0089308;8.0000000;0.0000000 -128.3737839;-56.8889428;53.7749769;6.1402874;-0.0087630;8.0000000;0.0000000 -128.5737431;-56.6910461;53.7463280;6.1385519;-0.0085951;8.0000000;0.0000000 -128.7737022;-56.4931996;53.7173391;6.1368500;-0.0084273;8.0000000;0.0000000 -128.9736614;-56.2954021;53.6880167;6.1351817;-0.0082595;8.0000000;0.0000000 -129.1736206;-56.0976530;53.6583678;6.1335469;-0.0080917;8.0000000;0.0000000 -129.3735797;-55.8999530;53.6283990;6.1319457;-0.0079239;8.0000000;0.0000000 -129.5735389;-55.7022995;53.5981168;6.1303779;-0.0077566;8.0000000;0.0000000 -129.7734981;-55.5046941;53.5675282;6.1288437;-0.0075892;8.0000000;0.0000000 -129.9734572;-55.3071351;53.5366398;6.1273429;-0.0074220;8.0000000;0.0000000 -130.1734164;-55.1096220;53.5054582;6.1258755;-0.0072550;8.0000000;0.0000000 -130.3733756;-54.9121550;53.4739902;6.1244415;-0.0070879;8.0000000;0.0000000 -130.5733347;-54.7147317;53.4422421;6.1230408;-0.0069212;8.0000000;0.0000000 -130.7732939;-54.5173533;53.4102210;6.1216736;-0.0067544;8.0000000;0.0000000 -130.9732531;-54.3200182;53.3779333;6.1203396;-0.0065878;8.0000000;0.0000000 -131.1732122;-54.1227255;53.3453857;6.1190390;-0.0064214;8.0000000;0.0000000 -131.3731714;-53.9254756;53.3125849;6.1177716;-0.0062549;8.0000000;0.0000000 -131.5731305;-53.7282657;53.2795372;6.1165375;-0.0060888;8.0000000;0.0000000 -131.7730897;-53.5310970;53.2462495;6.1153366;-0.0059227;8.0000000;0.0000000 -131.9730489;-53.3339676;53.2127284;6.1141689;-0.0057568;8.0000000;0.0000000 -132.1730080;-53.1368767;53.1789803;6.1130343;-0.0055910;8.0000000;0.0000000 -132.3729672;-52.9398244;53.1450120;6.1119329;-0.0054252;8.0000000;0.0000000 -132.5729264;-52.7428081;53.1108298;6.1108646;-0.0052598;8.0000000;0.0000000 -132.7728855;-52.5458285;53.0764405;6.1098294;-0.0050944;8.0000000;0.0000000 -132.9728447;-52.3488838;53.0418506;6.1088273;-0.0049292;8.0000000;0.0000000 -133.1728039;-52.1519732;53.0070665;6.1078581;-0.0047642;8.0000000;0.0000000 -133.3727630;-51.9550964;52.9720949;6.1069220;-0.0045992;8.0000000;0.0000000 -133.5727222;-51.7582509;52.9369422;6.1060188;-0.0044346;8.0000000;0.0000000 -133.7726814;-51.5614374;52.9016150;6.1051485;-0.0042700;8.0000000;0.0000000 -133.9726405;-51.3646538;52.8661198;6.1043112;-0.0041056;8.0000000;0.0000000 -134.1725997;-51.1678994;52.8304630;6.1035066;-0.0039414;8.0000000;0.0000000 -134.3725589;-50.9711737;52.7946512;6.1027349;-0.0037772;8.0000000;0.0000000 -134.5725180;-50.7744742;52.7586907;6.1019960;-0.0036135;8.0000000;0.0000000 -134.7724772;-50.5778013;52.7225882;6.1012898;-0.0034498;8.0000000;0.0000000 -134.9724364;-50.3811533;52.6863500;6.1006163;-0.0032863;8.0000000;0.0000000 -135.1723955;-50.1845289;52.6499826;6.0999755;-0.0031231;8.0000000;0.0000000 -135.3723547;-49.9879279;52.6134925;6.0993674;-0.0029599;8.0000000;0.0000000 -135.5723138;-49.7913476;52.5768859;6.0987918;-0.0027971;8.0000000;0.0000000 -135.7722730;-49.5947885;52.5401694;6.0982487;-0.0026344;8.0000000;0.0000000 -135.9722322;-49.3982485;52.5033494;6.0977382;-0.0024719;8.0000000;0.0000000 -136.1721913;-49.2017267;52.4664322;6.0972602;-0.0023096;8.0000000;0.0000000 -136.3721505;-49.0052224;52.4294244;6.0968146;-0.0021474;8.0000000;0.0000000 -136.5721097;-48.8087332;52.3923320;6.0964013;-0.0019857;8.0000000;0.0000000 -136.7720688;-48.6122594;52.3551617;6.0960205;-0.0018240;8.0000000;0.0000000 -136.9720280;-48.4157989;52.3179197;6.0956719;-0.0016626;8.0000000;0.0000000 -137.1719872;-48.2193507;52.2806124;6.0953556;-0.0015014;8.0000000;0.0000000 -137.3719463;-48.0229143;52.2432463;6.0950714;-0.0013402;8.0000000;0.0000000 -137.5719055;-47.8264871;52.2058273;6.0948195;-0.0011796;8.0000000;0.0000000 -137.7718647;-47.6300693;52.1683621;6.0945997;-0.0010190;8.0000000;0.0000000 -137.9718238;-47.4336589;52.1308568;6.0944120;-0.0008586;8.0000000;0.0000000 -138.1717830;-47.2372548;52.0933178;6.0942563;-0.0006986;8.0000000;0.0000000 -138.3717422;-47.0408566;52.0557515;6.0941326;-0.0005385;8.0000000;0.0000000 -138.5717013;-46.8444615;52.0181639;6.0940409;-0.0003790;8.0000000;0.0000000 -138.7716605;-46.6480699;51.9805614;6.0939810;-0.0002195;8.0000000;0.0000000 -138.9716197;-46.4516798;51.9429504;6.0939531;-0.0000604;8.0000000;0.0000000 -139.1715788;-46.2552900;51.9053369;6.0939569;0.0000986;8.0000000;0.0000000 -139.3715380;-46.0589001;51.8677274;6.0939925;0.0002575;8.0000000;0.0000000 -139.5714971;-45.8625072;51.8301279;6.0940598;0.0004158;8.0000000;0.0000000 -139.7714563;-45.6661120;51.7925448;6.0941588;0.0005742;8.0000000;0.0000000 -139.9714155;-45.4697121;51.7549842;6.0942894;0.0007322;8.0000000;0.0000000 -140.1713746;-45.2733067;51.7174523;6.0944516;0.0008900;8.0000000;0.0000000 -140.3713338;-45.0768953;51.6799556;6.0946453;0.0010478;8.0000000;0.0000000 -140.5712930;-44.8804749;51.6424997;6.0948706;0.0012050;8.0000000;0.0000000 -140.7712521;-44.6840463;51.6050914;6.0951272;0.0013622;8.0000000;0.0000000 -140.9712113;-44.4876073;51.5677365;6.0954153;0.0015191;8.0000000;0.0000000 -141.1711705;-44.2911567;51.5304412;6.0957347;0.0016757;8.0000000;0.0000000 -141.3711296;-44.0946945;51.4932119;6.0960854;0.0018323;8.0000000;0.0000000 -141.5710888;-43.8982174;51.4560544;6.0964674;0.0019884;8.0000000;0.0000000 -141.7710480;-43.7017265;51.4189751;6.0968806;0.0021445;8.0000000;0.0000000 -141.9710071;-43.5052193;51.3819801;6.0973250;0.0023002;8.0000000;0.0000000 -142.1709663;-43.3086950;51.3450754;6.0978005;0.0024558;8.0000000;0.0000000 -142.3709255;-43.1121535;51.3082674;6.0983071;0.0026113;8.0000000;0.0000000 -142.5708846;-42.9155914;51.2715617;6.0988448;0.0027663;8.0000000;0.0000000 -142.7708438;-42.7190100;51.2349650;6.0994134;0.0029212;8.0000000;0.0000000 -142.9708030;-42.5224070;51.1984830;6.1000130;0.0030760;8.0000000;0.0000000 -143.1707621;-42.3257813;51.1621220;6.1006435;0.0032304;8.0000000;0.0000000 -143.3707213;-42.1291333;51.1258881;6.1013049;0.0033849;8.0000000;0.0000000 -143.5706804;-41.9324591;51.0897870;6.1019971;0.0035388;8.0000000;0.0000000 -143.7706396;-41.7357606;51.0538254;6.1027202;0.0036928;8.0000000;0.0000000 -143.9705988;-41.5390352;51.0180089;6.1034739;0.0038465;8.0000000;0.0000000 -144.1705579;-41.3422821;50.9823437;6.1042584;0.0039999;8.0000000;0.0000000 -144.3705171;-41.1455018;50.9468361;6.1050736;0.0041534;8.0000000;0.0000000 -144.5704763;-40.9486901;50.9114916;6.1059194;0.0043064;8.0000000;0.0000000 -144.7704354;-40.7518495;50.8763169;6.1067958;0.0044595;8.0000000;0.0000000 -144.9703946;-40.5549770;50.8413175;6.1077028;0.0046123;8.0000000;0.0000000 -145.1703538;-40.3580722;50.8064998;6.1086403;0.0047649;8.0000000;0.0000000 -145.3703129;-40.1611356;50.7718699;6.1096084;0.0049175;8.0000000;0.0000000 -145.5702721;-39.9641629;50.7374332;6.1106069;0.0050698;8.0000000;0.0000000 -145.7702313;-39.7671570;50.7031966;6.1116359;0.0052220;8.0000000;0.0000000 -145.9701904;-39.5701149;50.6691656;6.1126953;0.0053740;8.0000000;0.0000000 -146.1701496;-39.3730361;50.6353463;6.1137850;0.0055259;8.0000000;0.0000000 -146.3701088;-39.1759215;50.6017450;6.1149052;0.0056778;8.0000000;0.0000000 -146.5700679;-38.9787665;50.5683671;6.1160557;0.0058293;8.0000000;0.0000000 -146.7700271;-38.7815745;50.5352194;6.1172364;0.0059809;8.0000000;0.0000000 -146.9699863;-38.5843424;50.5023074;6.1184475;0.0061324;8.0000000;0.0000000 -147.1699454;-38.3870698;50.4696373;6.1196889;0.0062837;8.0000000;0.0000000 -147.3699046;-38.1897579;50.4372153;6.1209605;0.0064350;8.0000000;0.0000000 -147.5698637;-37.9924020;50.4050468;6.1222623;0.0065861;8.0000000;0.0000000 -147.7698229;-37.7950057;50.3731385;6.1235944;0.0067373;8.0000000;0.0000000 -147.9697821;-37.5975658;50.3414961;6.1249567;0.0068883;8.0000000;0.0000000 -148.1697412;-37.4000824;50.3101257;6.1263492;0.0070392;8.0000000;0.0000000 -148.3697004;-37.2025566;50.2790334;6.1277718;0.0071902;8.0000000;0.0000000 -148.5696596;-37.0049838;50.2482249;6.1292246;0.0073413;8.0000000;0.0000000 -148.7696187;-36.8073679;50.2177066;6.1307077;0.0074924;8.0000000;0.0000000 -148.9695779;-36.6097057;50.1874844;6.1322210;0.0076443;8.0000000;0.0000000 -149.1695371;-36.4119974;50.1575643;6.1337648;0.0077969;8.0000000;0.0000000 -149.3694962;-36.2142441;50.1279527;6.1353391;0.0079496;8.0000000;0.0000000 -149.5694554;-36.0164418;50.0986551;6.1369442;0.0081041;8.0000000;0.0000000 -149.7694146;-35.8185939;50.0696784;6.1385801;0.0082587;8.0000000;0.0000000 -149.9693737;-35.6206977;50.0410283;6.1402471;0.0084143;8.0000000;0.0000000 -150.1693329;-35.4227535;50.0127113;6.1419452;0.0085706;8.0000000;0.0000000 -150.3692921;-35.2247623;49.9847336;6.1436746;0.0087270;8.0000000;0.0000000 -150.5692512;-35.0267205;49.9571013;6.1454354;0.0088850;8.0000000;0.0000000 -150.7692104;-34.8286316;49.9298210;6.1472279;0.0090431;8.0000000;0.0000000 -150.9691696;-34.6304930;49.9028990;6.1490520;0.0092020;8.0000000;0.0000000 -151.1691287;-34.4323052;49.8763415;6.1509080;0.0093617;8.0000000;0.0000000 -151.3690879;-34.2340689;49.8501552;6.1527959;0.0095215;8.0000000;0.0000000 -151.5690470;-34.0357815;49.8243462;6.1547159;0.0096826;8.0000000;0.0000000 -151.7690062;-33.8374458;49.7989213;6.1566681;0.0098438;8.0000000;0.0000000 -151.9689654;-33.6390598;49.7738867;6.1586527;0.0100059;8.0000000;0.0000000 -152.1689245;-33.4406242;49.7492492;6.1606697;0.0101686;8.0000000;0.0000000 -152.3688837;-33.2421398;49.7250152;6.1627193;0.0103315;8.0000000;0.0000000 -152.5688429;-33.0436044;49.7011913;6.1648016;0.0104957;8.0000000;0.0000000 -152.7688020;-32.8450203;49.6777841;6.1669167;0.0106598;8.0000000;0.0000000 -152.9687612;-32.6463864;49.6548003;6.1690647;0.0108247;8.0000000;0.0000000 -153.1687204;-32.4477032;49.6322464;6.1712457;0.0109900;8.0000000;0.0000000 -153.3686795;-32.2489715;49.6101293;6.1734598;0.0111555;8.0000000;0.0000000 -153.5686387;-32.0501900;49.5884554;6.1757071;0.0113219;8.0000000;0.0000000 -153.7685979;-31.8513607;49.5672317;6.1779876;0.0114883;8.0000000;0.0000000 -153.9685570;-31.6524829;49.5464648;6.1803015;0.0116556;8.0000000;0.0000000 -154.1685162;-31.4535572;49.5261614;6.1826490;0.0118237;8.0000000;0.0000000 -154.3684754;-31.2545843;49.5063284;6.1850300;0.0119917;8.0000000;0.0000000 -154.5684345;-31.0555640;49.4869726;6.1874445;0.0121586;8.0000000;0.0000000 -154.7683937;-30.8564975;49.4681007;6.1898925;0.0123255;8.0000000;0.0000000 -154.9683529;-30.6573851;49.4497194;6.1923722;0.0124671;8.0000000;0.0000000 -155.1683120;-30.4582275;49.4318345;6.1948776;0.0125919;8.0000000;0.0000000 -155.3682712;-30.2590256;49.4144511;6.1974079;0.0127082;8.0000000;0.0000000 -155.5682303;-30.0597810;49.3975737;6.1999534;0.0127528;8.0000000;0.0000000 -155.7681895;-29.8604927;49.3812043;6.2025079;0.0127972;8.0000000;0.0000000 -155.9681487;-29.6611648;49.3653446;6.2050616;0.0126826;8.0000000;0.0000000 -156.1681078;-29.4617967;49.3499904;6.2075759;0.0124663;8.0000000;0.0000000 -156.3680670;-29.2623882;49.3351329;6.2100468;0.0122300;8.0000000;0.0000000 -156.5680262;-29.0629490;49.3207627;6.2124530;0.0118366;8.0000000;0.0000000 -156.7679853;-28.8634718;49.3068642;6.2147805;0.0114435;8.0000000;0.0000000 -156.9679445;-28.6639654;49.2934224;6.2170292;0.0110460;8.0000000;0.0000000 -157.1679037;-28.4644298;49.2804213;6.2191979;0.0106458;8.0000000;0.0000000 -157.3678628;-28.2648644;49.2678447;6.2212867;0.0102468;8.0000000;0.0000000 -157.5678220;-28.0652776;49.2556774;6.2232965;0.0098559;8.0000000;0.0000000 -157.7677812;-27.8656643;49.2439033;6.2252282;0.0094650;8.0000000;0.0000000 -157.9677403;-27.6660307;49.2325071;6.2270817;0.0090738;8.0000000;0.0000000 -158.1676995;-27.4663766;49.2214731;6.2288570;0.0086822;8.0000000;0.0000000 -158.3676587;-27.2667017;49.2107856;6.2305539;0.0082909;8.0000000;0.0000000 -158.5676178;-27.0670127;49.2004294;6.2321727;0.0079007;8.0000000;0.0000000 -158.7675770;-26.8673047;49.1903885;6.2337136;0.0075105;8.0000000;0.0000000 -158.9675362;-26.6675834;49.1806476;6.2351764;0.0071206;8.0000000;0.0000000 -159.1674953;-26.4678482;49.1711910;6.2365612;0.0067309;8.0000000;0.0000000 -159.3674545;-26.2680989;49.1620033;6.2378682;0.0063413;8.0000000;0.0000000 -159.5674136;-26.0683410;49.1530689;6.2390973;0.0059524;8.0000000;0.0000000 -159.7673728;-25.8685701;49.1443723;6.2402487;0.0055635;8.0000000;0.0000000 -159.9673320;-25.6687911;49.1358979;6.2413223;0.0051752;8.0000000;0.0000000 -160.1672911;-25.4690032;49.1276302;6.2423183;0.0047873;8.0000000;0.0000000 -160.3672503;-25.2692058;49.1195538;6.2432368;0.0043995;8.0000000;0.0000000 -160.5672095;-25.0694042;49.1116532;6.2440779;0.0040125;8.0000000;0.0000000 -160.7671686;-24.8695940;49.1039129;6.2448415;0.0036256;8.0000000;0.0000000 -160.9671278;-24.6697796;49.0963174;6.2455278;0.0032392;8.0000000;0.0000000 -161.1670870;-24.4699601;49.0888514;6.2461369;0.0028532;8.0000000;0.0000000 -161.3670461;-24.2701349;49.0814993;6.2466689;0.0024673;8.0000000;0.0000000 -161.5670053;-24.0703087;49.0742459;6.2471237;0.0020823;8.0000000;0.0000000 -161.7669645;-23.8704773;49.0670757;6.2475016;0.0016973;8.0000000;0.0000000 -161.9669236;-23.6706447;49.0599733;6.2478025;0.0013129;8.0000000;0.0000000 -162.1668828;-23.4708100;49.0529233;6.2480267;0.0009290;8.0000000;0.0000000 -162.3668420;-23.2709728;49.0459105;6.2481741;0.0005453;8.0000000;0.0000000 -162.5668011;-23.0711370;49.0389195;6.2482449;0.0001627;8.0000000;0.0000000 -162.7667603;-22.8712991;49.0319349;6.2482391;-0.0002198;8.0000000;0.0000000 -162.9667195;-22.6714626;49.0249416;6.2481570;-0.0006016;8.0000000;0.0000000 -163.1666786;-22.4716268;49.0179243;6.2479986;-0.0009828;8.0000000;0.0000000 -163.3666378;-22.2717913;49.0108676;6.2477639;-0.0013637;8.0000000;0.0000000 -163.5665969;-22.0719596;49.0037565;6.2474534;-0.0017425;8.0000000;0.0000000 -163.7665561;-21.8721287;48.9965758;6.2470671;-0.0021213;8.0000000;0.0000000 -163.9665153;-21.6723019;48.9893103;6.2466050;-0.0025004;8.0000000;0.0000000 -164.1664744;-21.4724785;48.9819449;6.2460671;-0.0028796;8.0000000;0.0000000 -164.3664336;-21.2726586;48.9744644;6.2454534;-0.0032569;8.0000000;0.0000000 -164.5663928;-21.0728452;48.9668539;6.2447655;-0.0036234;8.0000000;0.0000000 -164.7663519;-20.8730359;48.9590985;6.2440043;-0.0039899;8.0000000;0.0000000 -164.9663111;-20.6732336;48.9511838;6.2431687;-0.0043749;8.0000000;0.0000000 -165.1662703;-20.4734382;48.9430942;6.2422544;-0.0047699;8.0000000;0.0000000 -165.3662294;-20.2736497;48.9348140;6.2412599;-0.0052402;8.0000000;-3.0247383 -165.5661886;-20.0738705;48.9263225;6.2401235;-0.0061261;7.9240363;-5.1449641 -165.7661478;-19.8741024;48.9175864;6.2388100;-0.0070121;7.7931243;-5.0137339 -165.9661069;-19.6743491;48.9085648;6.2371969;-0.0097656;7.6634002;-4.8374359 -166.1660661;-19.4746131;48.8991525;6.2348708;-0.0135000;7.5361212;-4.6407788 -166.3660253;-19.2749010;48.8892008;6.2317884;-0.0178495;7.4119627;-4.2806281 -166.5659844;-19.0752364;48.8785212;6.2274539;-0.0255065;7.2955664;-3.9419431 -166.7659436;-18.8756147;48.8668227;6.2215883;-0.0331588;7.1867123;-3.6521395 -166.9659027;-18.6760814;48.8538029;6.2142324;-0.0402145;7.0843684;-3.3921378 -167.1658619;-18.4766573;48.8391792;6.2055156;-0.0469720;6.9879681;-3.1477570 -167.3658211;-18.2773717;48.8226824;6.1954475;-0.0536655;6.8973076;-2.9311468 -167.5657802;-18.0782710;48.8040493;6.1840830;-0.0600005;6.8118010;-2.7219126 -167.7657394;-17.8794273;48.7830308;6.1714499;-0.0663660;6.7314256;-2.5194745 -167.9656986;-17.6808493;48.7593716;6.1575400;-0.0727444;6.6561630;-2.3211056 -168.1656577;-17.4826529;48.7328283;6.1423524;-0.0791653;6.5860651;-2.1251565 -168.3656169;-17.2849354;48.7031561;6.1258786;-0.0856347;6.5212241;-1.9290099 -168.5655761;-17.0876748;48.6700888;6.1080972;-0.0921795;6.4618045;-1.7312864 -168.7655352;-16.8911504;48.6334084;6.0890082;-0.0987966;6.4080063;-1.5295603 -168.9654944;-16.6953155;48.5928376;6.0685806;-0.1055044;6.3600979;-1.3212395 -169.1654536;-16.5004062;48.5481497;6.0468029;-0.1123211;6.3184221;-1.1051191 -169.3654127;-16.3066161;48.4991129;6.0236614;-0.1192262;6.2833510;-0.9447773 -169.5653719;-16.1139202;48.4454334;5.9991068;-0.1262965;6.2532125;-0.9357357 -169.7653311;-15.9227738;48.3869451;5.9731433;-0.1334853;6.2232185;-0.9267806 -169.9652902;-15.7331649;48.3233452;5.9457149;-0.1408467;6.1933684;-0.9179111 -170.1652494;-15.5454531;48.2544413;5.9167985;-0.1483897;6.1636615;-0.9091266 -170.3652086;-15.3599348;48.1800260;5.8863723;-0.1560799;6.1340970;-0.9004261 -170.5651677;-15.1767179;48.0998081;5.8543554;-0.1640927;6.1046744;-0.8918089 -170.7651269;-14.9963318;48.0136702;5.8207390;-0.1722460;6.0753929;-0.8832742 -170.9650860;-14.8189650;47.9213433;5.7854574;-0.1807157;6.0462518;-0.8748212 -171.1650452;-14.6450622;47.8226751;5.7484489;-0.1894827;6.0172505;-0.8664490 -171.3650044;-14.4750506;47.7175084;5.7096775;-0.1984653;5.9883884;-0.8581570 -171.5649635;-14.3093249;47.6056645;5.6690506;-0.2079512;5.9596646;-0.8499443 -171.7649227;-14.1483817;47.4870199;5.6265027;-0.2176225;5.9310787;-0.8418102 -171.9648819;-13.9928154;47.3615370;5.5819966;-0.2278472;5.9026298;-0.8337540 -172.1648410;-13.8430765;47.2290570;5.5353799;-0.2384636;5.8743174;-0.8257748 -172.3648002;-13.6998175;47.0895855;5.4866259;-0.2493019;5.8461409;-0.8178720 -172.5647594;-13.5637940;46.9432671;5.4356731;-0.2607745;5.8180994;-0.8100449 -172.7647185;-13.4353710;46.7898050;5.3823262;-0.2723222;5.7901925;-0.8022927 -172.9646777;-13.3157367;46.6299068;5.3267161;-0.2848572;5.7624194;-0.7946146 -173.1646369;-13.2052588;46.4632512;5.2684064;-0.2984055;5.7347796;-0.7870100 -173.3645960;-13.1048514;46.2901874;5.2074753;-0.3066021;5.7072723;-0.7794782 -173.5645552;-13.0153459;46.1116016;5.1466270;-0.3028513;5.6798969;-0.7720185 -173.7645144;-12.9366628;45.9275542;5.0862074;-0.3011005;5.6526529;-0.7646302 -173.9644735;-12.8692659;45.7393942;5.0268694;-0.2905110;5.6255395;-0.7573126 -174.1644327;-12.8128849;45.5475589;4.9700282;-0.2781829;5.5985562;-0.7500650 -174.3643919;-12.7672434;45.3527954;4.9154954;-0.2671012;5.5717024;-0.7428868 -174.5643510;-12.7320938;45.1560206;4.8631613;-0.2566020;5.5449773;-0.7357773 -174.7643102;-12.7070726;44.9575987;4.8128142;-0.2470001;5.5183804;-0.7287358 -174.9642693;-12.6918848;44.7582207;4.7643236;-0.2379776;5.4919111;-0.7217617 -175.1642285;-12.6862007;44.5583544;4.7176032;-0.2294130;5.4655688;-0.7148543 -175.3641877;-12.6896910;44.3584273;4.6725264;-0.2214921;5.4393528;-0.7080131 -175.5641468;-12.7020319;44.1588365;4.6290011;-0.2138509;5.4132625;-0.7012373 -175.7641060;-12.7228907;43.9600010;4.5869713;-0.2066537;5.3872974;-0.6945263 -175.9640652;-12.7519551;43.7621456;4.5463266;-0.1998323;5.3614569;-0.6878796 -176.1640243;-12.7888977;43.5656312;4.5070290;-0.1932570;5.3357402;-0.6878796 -176.3639835;-12.8333934;43.3707435;4.4690222;-0.1870202;5.3098991;-0.6092222 -176.5639427;-12.8851739;43.1775479;4.4322266;-0.1809185;5.2869073;-0.3757228 -176.7639018;-12.9438783;42.9864526;4.3966493;-0.1750406;5.2726778;-0.1743801 -176.9638610;-13.0092556;42.7974676;4.3622128;-0.1693663;5.2660605;0.0001761 -177.1638202;-13.0809928;42.6108118;4.3289016;-0.1638126;5.2660672;0.1541717 -177.3637793;-13.1587707;42.4266851;4.2966971;-0.1584373;5.2719180;0.2890508 -177.5637385;-13.2424042;42.2449790;4.2655391;-0.1530982;5.2828701;0.4114743 -177.7636977;-13.3315087;42.0660237;4.2354565;-0.1478727;5.2984217;0.5212271 -177.9636568;-13.4258896;41.8897349;4.2063985;-0.1427539;5.3180561;0.6203172 -178.1636160;-13.5252674;41.7162061;4.1783595;-0.1376801;5.3413291;0.7120282 -178.3635752;-13.6293371;41.5455550;4.1513390;-0.1326931;5.3679186;0.7963478 -178.5635343;-13.7379731;41.3776081;4.1252932;-0.1277367;5.3975016;0.8759963 -178.7634935;-13.8508085;41.2125710;4.1002468;-0.1228277;5.4298574;0.9513387 -178.9634526;-13.9676822;41.0503290;4.0761507;-0.1183494;5.4647789;1.0116948 -179.1634118;-14.0883702;40.8908885;4.0529016;-0.1141785;5.5016728;1.0618326 -179.3633710;-14.2126265;40.7342948;4.0304899;-0.1101835;5.5401309;1.1064785 -179.5633301;-14.3403716;40.5804155;4.0086094;-0.1086267;5.5799240;1.0756057 -179.7632893;-14.4713915;40.4293905;3.9870441;-0.1070945;5.6183366;1.0476449 -179.9632485;-14.6056255;40.2811943;3.9657760;-0.1056776;5.6554998;1.0193910 -180.1632076;-14.7429680;40.1358602;3.9447761;-0.1043624;5.6914279;0.9910946 -180.3631668;-14.8832904;39.9934469;3.9240390;-0.1030678;5.7261425;0.9652452 -180.5631260;-15.0265507;39.8539206;3.9035892;-0.1014550;5.7597507;0.9528319 -180.7630851;-15.1725892;39.7173506;3.8834615;-0.0998786;5.7927353;0.9413716 -180.9630443;-15.3213336;39.5837175;3.8636451;-0.0983211;5.8251399;0.9313194 -181.1630035;-15.4726800;39.4530314;3.8441393;-0.0967774;5.8570219;0.9227157 -181.3629626;-15.6265080;39.3253140;3.8249411;-0.0952682;5.8884393;0.9147104 -181.5629218;-15.7827700;39.2005269;3.8060375;-0.0937938;5.9194194;0.9071946 -181.7628810;-15.9413249;39.0787078;3.7874283;-0.0923484;5.9499857;0.9002856 -181.9628401;-16.1021088;38.9598323;3.7691043;-0.0909310;5.9801648;0.8939402 -182.1627993;-16.2650306;38.8438975;3.7510614;-0.0895354;6.0099812;0.8882940 -182.3627585;-16.4299854;38.7309094;3.7332966;-0.0881675;6.0394635;0.8830568 -182.5627176;-16.5969318;38.6208301;3.7158000;-0.0868243;6.0686300;0.8782705 -182.7626768;-16.7657466;38.5136770;3.6985716;-0.0855043;6.0975000;0.8739297 -182.9626359;-16.9363746;38.4094220;3.6816039;-0.0842110;6.1260923;0.8698445 -183.1625951;-17.1087366;38.3080535;3.6648924;-0.0829390;6.1544190;0.8661603 -183.3625543;-17.2827416;38.2095654;3.6484344;-0.0816892;6.1824968;0.8627950 -183.5625134;-17.4583542;38.1139205;3.6322224;-0.0804562;6.2103393;0.8599023 -183.7624726;-17.6354672;38.0211214;3.6162566;-0.0792418;6.2379648;0.8573696 -183.9624318;-17.8140339;37.9311375;3.6005310;-0.0780499;6.2653877;0.8549915 -184.1623909;-17.9939853;37.8439503;3.5850416;-0.0768762;6.2926155;0.8529033 -184.3623501;-18.1752432;37.7595454;3.5697862;-0.0757197;6.3196599;0.8511053 -184.5623093;-18.3577774;37.6778858;3.5547599;-0.0745685;6.3465324;0.8500411 -184.7622684;-18.5414954;37.5989628;3.5399635;-0.0734321;6.3732582;0.8492752 -184.9622276;-18.7263574;37.5227438;3.5253922;-0.0723134;6.3998485;0.8486547 -185.1621868;-18.9123037;37.4492051;3.5110429;-0.0712088;6.4263095;0.8482986 -185.3621459;-19.0992677;37.3783255;3.4969140;-0.0701183;6.4526509;0.8481780 -185.5621051;-19.2872235;37.3100682;3.4830006;-0.0690398;6.4788815;0.8483535 -185.7620643;-19.4760920;37.2444163;3.4693026;-0.0679730;6.5050118;0.8488101 -185.9620234;-19.6658398;37.1813359;3.4558164;-0.0669180;6.5310514;0.8495141 -186.1619826;-19.8564159;37.1207997;3.4425401;-0.0658725;6.5570092;0.8505431 -186.3619418;-20.0477640;37.0627816;3.4294723;-0.0648380;6.5828958;0.8518023 -186.5619009;-20.2398618;37.0072453;3.4166097;-0.0638118;6.6087191;0.8533924 -186.7618601;-20.4326429;36.9541672;3.4039520;-0.0627948;6.6344898;0.8552497 -186.9618192;-20.6260791;36.9035129;3.3914965;-0.0617859;6.6602166;0.8573950 -187.1617784;-20.8201271;36.8552521;3.3792421;-0.0607837;6.6859086;0.8598811 -187.3617376;-21.0147406;36.8093549;3.3671876;-0.0597899;6.7115762;0.8626003 -187.5616967;-21.2098994;36.7657853;3.3553308;-0.0588011;6.7372268;0.8656991 -187.7616559;-21.4055494;36.7245150;3.3436714;-0.0578193;6.7628718;0.8690577 -187.9616151;-21.6016666;36.6855087;3.3322075;-0.0568433;6.7885187;0.8727181 -188.1615742;-21.7982149;36.6487340;3.3209383;-0.0558720;6.8141766;0.8767180 -188.3615334;-21.9951570;36.6141583;3.3098629;-0.0549071;6.8398551;0.8809577 -188.5614926;-22.1924741;36.5817456;3.2989798;-0.0539453;6.8655611;0.8855850 -188.7614517;-22.3901243;36.5514640;3.2882888;-0.0529888;6.8913055;0.8904735 -188.9614109;-22.5880862;36.5232781;3.2777884;-0.0520367;6.9170953;0.8956599 -189.1613701;-22.7863310;36.4971534;3.2674781;-0.0510880;6.9429387;0.9011760 -189.3613292;-22.9848296;36.4730556;3.2573571;-0.0501442;6.9688446;0.9069372 -189.5612884;-23.1835637;36.4509489;3.2474244;-0.0492035;6.9948192;0.9130255 -189.7612476;-23.3825033;36.4307987;3.2376794;-0.0482668;7.0208711;0.9193858 -189.9612067;-23.5816287;36.4125694;3.2281213;-0.0473347;7.0470072;0.9259743 -190.1611659;-23.7809181;36.3962256;3.2187492;-0.0464061;7.0732330;0.9328462 -190.3611251;-23.9803500;36.3817319;3.2095625;-0.0454815;7.0995554;0.9399617 -190.5610842;-24.1799057;36.3690524;3.2005600;-0.0445623;7.1259803;0.9472432 -190.7610434;-24.3795670;36.3581515;3.1917410;-0.0436461;7.1525111;0.9548190 -190.9610025;-24.5793148;36.3489936;3.1831047;-0.0427372;7.1791549;0.9624467 -191.1609617;-24.7791342;36.3415431;3.1746494;-0.0418332;7.2059118;0.9702593 -191.3609209;-24.9790103;36.3357642;3.1663746;-0.0409331;7.2327857;0.9783019 -191.5608800;-25.1789237;36.3316215;3.1582787;-0.0400431;7.2597817;0.9862452 -191.7608392;-25.3788676;36.3290797;3.1503605;-0.0391551;7.2868956;0.9945158 -191.9607984;-25.5788223;36.3281034;3.1426193;-0.0382758;7.3141351;1.0027518 -192.1607575;-25.7787795;36.3286574;3.1350531;-0.0374018;7.3414979;1.0111381 -192.3607167;-25.9787304;36.3307070;3.1276614;-0.0365312;7.3689866;1.0197762 -192.5606759;-26.1786543;36.3342170;3.1204429;-0.0356704;7.3966067;1.0283090 -192.7606350;-26.3785547;36.3391530;3.1133961;-0.0348111;7.4243539;1.0371954 -192.9605942;-26.5784113;36.3454803;3.1065208;-0.0339591;7.4522362;1.0461099 -193.1605534;-26.7782215;36.3531645;3.0998152;-0.0331113;7.4802529;1.0552228 -193.3605125;-26.9779813;36.3621717;3.0932787;-0.0322663;7.5084077;1.0646164 -193.5604717;-27.1776696;36.3724671;3.0869107;-0.0314291;7.5367065;1.0739930 -193.7604309;-27.3772982;36.3840178;3.0807096;-0.0305932;7.5651474;1.0837400 -193.9603900;-27.5768462;36.3967891;3.0746751;-0.0297696;7.5937384;1.0932023 -194.1603492;-27.7763164;36.4107482;3.0688041;-0.0289527;7.6224703;1.1027213 -194.3603084;-27.9757080;36.4258622;3.0630961;-0.0281409;7.6513432;1.1123904 -194.5602675;-28.1750008;36.4420972;3.0575484;-0.0273495;7.6803592;1.1212936 -194.7602267;-28.3742120;36.4594227;3.0521585;-0.0265591;7.7094970;1.1306051 -194.9601858;-28.5733215;36.4778054;3.0469266;-0.0257727;7.7387656;1.1401340 -195.1601450;-28.7723355;36.4972140;3.0418515;-0.0249886;7.7681693;1.1499828 -195.3601042;-28.9712559;36.5176175;3.0369330;-0.0242057;7.7977146;1.1602116 -195.5600633;-29.1700643;36.5389823;3.0321711;-0.0234248;7.8274097;1.1707627 -195.7600225;-29.3687807;36.5612793;3.0275650;-0.0226447;7.8572611;1.1817161 -195.9599817;-29.5673873;36.5844750;3.0231149;-0.0218656;7.8872773;1.1930562 -196.1599408;-29.7658924;36.6085391;3.0188205;-0.0210872;7.9174660;1.2047974 -196.3599000;-29.9642995;36.6334407;3.0146816;-0.0203094;7.9478354;1.2169414 -196.5598592;-30.1625942;36.6591465;3.0106984;-0.0195319;7.9783937;0.8632631 -196.7598183;-30.3607960;36.6856278;3.0068704;-0.0187550;8.0000000;0.0000000 -196.9597775;-30.5588910;36.7128514;3.0031979;-0.0179780;8.0000000;0.0000000 -197.1597367;-30.7568886;36.7407872;2.9996807;-0.0172012;8.0000000;0.0000000 -197.3596958;-30.9547934;36.7694044;2.9963187;-0.0164247;8.0000000;0.0000000 -197.5596550;-31.1525949;36.7986703;2.9931122;-0.0156477;8.0000000;0.0000000 -197.7596142;-31.3503115;36.8285561;2.9900609;-0.0148711;8.0000000;0.0000000 -197.9595733;-31.5479332;36.8590289;2.9871650;-0.0140939;8.0000000;0.0000000 -198.1595325;-31.7454697;36.8900587;2.9844245;-0.0133166;8.0000000;0.0000000 -198.3594916;-31.9429263;36.9216150;2.9818394;-0.0125394;8.0000000;0.0000000 -198.5594508;-32.1402968;36.9536653;2.9794098;-0.0117616;8.0000000;0.0000000 -198.7594100;-32.3375974;36.9861806;2.9771357;-0.0109841;8.0000000;0.0000000 -198.9593691;-32.5348220;37.0191285;2.9750171;-0.0102050;8.0000000;0.0000000 -199.1593283;-32.7319801;37.0524790;2.9730545;-0.0094253;8.0000000;0.0000000 -199.3592875;-32.9290774;37.0862014;2.9712490;-0.0085855;8.0000000;0.0000000 -199.5592466;-33.1261113;37.1202602;2.9696400;-0.0075084;8.0000000;0.0000000 -199.7592058;-33.3230996;37.1546157;2.9682463;-0.0064314;8.0000000;0.0000000 -199.9591650;-33.5200383;37.1892214;2.9671167;-0.0046621;8.0000000;0.0000000 -200.1591241;-33.7169472;37.2240109;2.9663903;-0.0026034;8.0000000;0.0000000 -200.3590833;-33.9138419;37.2589035;2.9660762;-0.0005146;8.0000000;0.0000000 -200.5590425;-34.1107244;37.2938144;2.9661937;0.0016899;8.0000000;0.0000000 -200.7590016;-34.3076285;37.3286606;2.9667520;0.0038940;8.0000000;0.0000000 -200.9589608;-34.5045521;37.3633521;2.9677496;0.0060778;8.0000000;0.0000000 -201.1589200;-34.7015205;37.3978048;2.9691824;0.0082532;8.0000000;0.0000000 -201.3588791;-34.8985501;37.4319331;2.9710501;0.0104268;8.0000000;0.0000000 -201.5588383;-35.0956411;37.4656490;2.9733518;0.0125952;8.0000000;0.0000000 -201.7587975;-35.2928256;37.4988701;2.9760871;0.0147632;8.0000000;0.0000000 -201.9587566;-35.4901005;37.5315077;2.9792558;0.0169293;8.0000000;0.0000000 -202.1587158;-35.6874870;37.5634777;2.9828574;0.0190946;8.0000000;0.0000000 -202.3586749;-35.8849983;37.5946945;2.9868921;0.0212591;8.0000000;0.0000000 -202.5586341;-36.0826323;37.6250701;2.9913592;0.0234220;8.0000000;0.0000000 -202.7585933;-36.2804143;37.6545210;2.9962590;0.0255852;8.0000000;0.0000000 -202.9585524;-36.4783388;37.6829588;3.0015910;0.0277464;8.0000000;0.0000000 -203.1585116;-36.6764197;37.7102984;3.0073553;0.0299078;8.0000000;0.0000000 -203.3584708;-36.8746638;37.7364532;3.0135519;0.0320691;8.0000000;0.0000000 -203.5584299;-37.0730656;37.7613356;3.0201802;0.0342294;8.0000000;0.0000000 -203.7583891;-37.2716383;37.7848600;3.0272410;0.0363915;8.0000000;0.0000000 -203.9583483;-37.4703736;37.8069385;3.0347338;0.0385520;8.0000000;0.0000000 -204.1583074;-37.6692739;37.8274844;3.0426588;0.0407145;8.0000000;0.0000000 -204.3582666;-37.8683368;37.8464105;3.0510164;0.0428782;8.0000000;0.0000000 -204.5582258;-38.0675517;37.8636290;3.0598065;0.0450419;8.0000000;0.0000000 -204.7581849;-38.2669154;37.8790526;3.0690298;0.0472099;8.0000000;0.0000000 -204.9581441;-38.4664155;37.8925936;3.0786866;0.0493770;8.0000000;0.0000000 -205.1581033;-38.6660391;37.9041641;3.0887770;0.0515488;8.0000000;0.0000000 -205.3580624;-38.8657712;37.9136764;3.0993022;0.0537241;8.0000000;0.0000000 -205.5580216;-39.0655956;37.9210426;3.1102624;0.0559008;8.0000000;0.0000000 -205.7579808;-39.2654864;37.9261746;3.1216586;0.0580861;8.0000000;0.0000000 -205.9579399;-39.4654275;37.9289847;3.1334923;0.0602731;8.0000000;0.0000000 -206.1578991;-39.6653856;37.9293848;3.1457639;0.0624697;8.0000000;0.0000000 -206.3578582;-39.8653302;37.9272873;3.1584756;0.0646741;8.0000000;0.0000000 -206.5578174;-40.0652387;37.9226040;3.1716288;0.0668843;8.0000000;0.0000000 -206.7577766;-40.2650564;37.9152480;3.1852248;0.0691090;8.0000000;0.0000000 -206.9577357;-40.4647633;37.9051309;3.1992671;0.0713393;8.0000000;0.0000000 -207.1576949;-40.6643009;37.8921664;3.2137564;0.0735857;8.0000000;0.0000000 -207.3576541;-40.8636199;37.8762678;3.2286961;0.0758459;8.0000000;0.0000000 -207.5576132;-41.0626898;37.8573468;3.2440897;0.0781178;8.0000000;0.0000000 -207.7575724;-41.2614217;37.8353206;3.2599385;0.0804126;8.0000000;0.0000000 -207.9575316;-41.4597901;37.8100998;3.2762488;0.0827188;8.0000000;0.0000000 -208.1574907;-41.6577070;37.7816024;3.2930219;0.0850506;8.0000000;0.0000000 -208.3574499;-41.8551009;37.7497450;3.3102630;0.0874042;8.0000000;0.0000000 -208.5574091;-42.0519304;37.7144384;3.3279784;0.0897785;8.0000000;0.0000000 -208.7573682;-42.2480679;37.6756095;3.3461695;0.0921866;8.0000000;0.0000000 -208.9573274;-42.4434793;37.6331667;3.3648466;0.0946159;8.0000000;0.0000000 -209.1572866;-42.6380428;37.5870368;3.3840121;0.0970834;8.0000000;0.0000000 -209.3572457;-42.8316613;37.5371422;3.4036733;0.0995835;8.0000000;0.0000000 -209.5572049;-43.0242770;37.4833940;3.4238403;0.1021183;8.0000000;0.0000000 -209.7571641;-43.2157216;37.4257340;3.4445156;0.1047012;8.0000000;0.0000000 -209.9571232;-43.4059459;37.3640695;3.4657141;0.1073186;8.0000000;0.0000000 -210.1570824;-43.5947907;37.2983413;3.4874399;0.1099920;8.0000000;0.0000000 -210.3570415;-43.7821295;37.2284815;3.5097038;0.1127139;8.0000000;0.0000000 -210.5570007;-43.9678793;37.1544041;3.5325207;0.1154899;8.0000000;0.0000000 -210.7569599;-44.1518308;37.0760733;3.5558948;0.1183323;8.0000000;0.0000000 -210.9569190;-44.3339100;36.9933973;3.5798472;0.1212327;8.0000000;0.0000000 -211.1568782;-44.5139172;36.9063386;3.6043856;0.1242143;8.0000000;-0.8264465 -211.3568374;-44.6916922;36.8148437;3.6295255;0.1272667;7.9793163;-1.5236253 -211.5567965;-44.8671139;36.7188367;3.6552890;0.1304102;7.9410430;-1.5090440 -211.7567557;-45.0399348;36.6183102;3.6816848;0.1336444;7.9029532;-1.4946023 -211.9567149;-45.2100394;36.5131819;3.7087420;0.1369845;7.8650461;-1.4802987 -212.1566740;-45.3771866;36.4034430;3.7364774;0.1404441;7.8273208;-1.4661321 -212.3566332;-45.5411746;36.2890621;3.7649130;0.1440270;7.7897765;-1.4521010 -212.5565924;-45.7018264;36.1699867;3.7940914;0.1478141;7.7524123;-1.4382042 -212.7565515;-45.8588590;36.0462388;3.8240345;0.1517256;7.7152273;-1.4244404 -212.9565107;-46.0120911;35.9177619;3.8547876;0.1559064;7.6782207;-1.4108083 -213.1564699;-46.1612314;35.7845815;3.8863990;0.1603007;7.6413915;-1.3973066 -213.3564290;-46.3060201;35.6466958;3.9189015;0.1648127;7.6047390;-1.3839342 -213.5563882;-46.4462054;35.5040945;3.9523222;0.1694699;7.5682624;-1.3706898 -213.7563474;-46.5814520;35.3568538;3.9866885;0.1743287;7.5319607;-1.3575721 -213.9563065;-46.7115045;35.2049801;4.0218714;0.1771872;7.4958331;-1.3445799 -214.1562657;-46.8360927;35.0485982;4.0575491;0.1796952;7.4598788;-0.8431659 -214.3562248;-46.9549769;34.8878515;4.0936780;0.1804197;7.4372437;-1.3236429 -214.5561840;-47.0679939;34.7229313;4.1294344;0.1772826;7.4015704;-1.3109755 -214.7561432;-47.1751189;34.5540699;4.1645910;0.1743464;7.3660682;-1.2984293 -214.9561023;-47.2762711;34.3816272;4.1990469;0.1701169;7.3307364;-1.2860031 -215.1560615;-47.3715167;34.2058129;4.2326278;0.1657861;7.2955740;-1.2736959 -215.3560207;-47.4608852;34.0269310;4.2653647;0.1616334;7.2605802;-1.2615064 -215.5559798;-47.5444125;33.8452852;4.2972713;0.1575548;7.2257543;-1.2494337 -215.7559390;-47.6221964;33.6610496;4.3283861;0.1536380;7.1910955;-1.2374764 -215.9558982;-47.6942629;33.4745656;4.3587263;0.1498871;7.1566029;-1.2256336 -216.1558573;-47.7607199;33.2859740;4.3883343;0.1462672;7.1222757;-1.2139041 -216.3558165;-47.8216342;33.0955145;4.4172335;0.1427803;7.0881132;-1.2022869 -216.5557757;-47.8770787;32.9034209;4.4454391;0.1393760;7.0541146;-1.1907808 -216.7557348;-47.9271601;32.7098111;4.4729820;0.1360901;7.0202790;-1.1793849 -216.9556940;-47.9719428;32.5149619;4.4998703;0.1328914;6.9866057;-1.1680980 -217.1556532;-48.0115386;32.3189618;4.5261313;0.1297808;6.9530940;-1.1569192 -217.3556123;-48.0460352;32.1219974;4.5517808;0.1267650;6.9197430;-1.1458473 -217.5555715;-48.0755251;31.9242445;4.5768303;0.1238119;6.8865519;-1.1348814 -217.7555307;-48.1001152;31.7257824;4.6013024;0.1209431;6.8535201;-1.1240204 -217.9554898;-48.1198941;31.5268297;4.6252025;0.1181406;6.8206467;-1.1132634 -218.1554490;-48.1349701;31.3274385;4.6485514;0.1154010;6.7879310;-1.1026093 -218.3554081;-48.1454411;31.1277511;4.6713599;0.1127326;6.7553722;-1.0920572 -218.5553673;-48.1514078;30.9278970;4.6936380;0.1101158;6.7229695;-1.0816060 -218.7553265;-48.1529728;30.7279259;4.7154023;0.1075589;6.6907223;-1.0816060 -218.9552856;-48.1502373;30.5280074;4.7366571;0.1050584;6.6583189;-1.0578907 -219.1552448;-48.1433021;30.3281672;4.7574187;0.1026037;6.6264728;-0.8795128 -219.3552040;-48.1322682;30.1285104;4.7776950;0.1002043;6.5998794;-0.7171148 -219.5551631;-48.1172375;29.9291302;4.7974946;0.0978487;6.5781168;-0.5686368 -219.7551223;-48.0983059;29.7300536;4.8168301;0.0955356;6.5608088;-0.4326681 -219.9550815;-48.0755785;29.5314086;4.8357052;0.0932739;6.5476088;-0.3083983 -220.1550406;-48.0491479;29.3332025;4.8541332;0.0910462;6.5381837;-0.1939717 -220.3549998;-48.0191130;29.1355097;4.8721199;0.0888628;6.5322487;-0.0889016 -220.5549590;-47.9855723;28.9383943;4.8896732;0.0867180;6.5295268;0.0079200 -220.7549181;-47.9486144;28.7418672;4.9068026;0.0846036;6.5297693;0.0976038 -220.9548773;-47.9083424;28.5460198;4.9235116;0.0825353;6.5327575;0.1801308 -221.1548365;-47.8648405;28.3508488;4.9398109;0.0804924;6.5382688;0.2570202 -221.3547956;-47.8182026;28.1564022;4.9557048;0.0784851;6.5461245;0.3283554 -221.5547548;-47.7685213;27.9627209;4.9712005;0.0765111;6.5561468;0.3947128 -221.7547140;-47.7158785;27.7698067;4.9863048;0.0745590;6.5681743;0.4570224 -221.9546731;-47.6603701;27.5777154;5.0010206;0.0726368;6.5820730;0.5153065 -222.1546323;-47.6020751;27.3864419;5.0153544;0.0707325;6.5977092;0.5704355 -222.3545914;-47.5410801;27.1960109;5.0293094;0.0688443;6.6149750;0.6227768 -222.5545506;-47.4774713;27.0064428;5.0428872;0.0669658;6.6337737;0.6728792 -222.7545098;-47.4113275;26.8177367;5.0560914;0.0651027;6.6540251;0.7207226 -222.9544689;-47.3427347;26.6299131;5.0689232;0.0632428;6.6756483;0.7670670 -223.1544281;-47.2717715;26.4429701;5.0813841;0.0613930;6.6985853;0.8117901 -223.3543873;-47.1985183;26.2569111;5.0934763;0.0595519;6.7227743;0.8551285 -223.5543464;-47.1230551;26.0717385;5.1052004;0.0577135;6.7481609;0.8975262 -223.7543056;-47.0454608;25.8874510;5.1165576;0.0558850;6.7747039;0.9387850 -223.9542648;-46.9658099;25.7040372;5.1275497;0.0540560;6.8023562;0.9795397 -224.1542239;-46.8841829;25.5214991;5.1381763;0.0522326;6.8310897;1.0196185 -224.3541831;-46.8006536;25.3398229;5.1484389;0.0504138;6.8608710;1.0591932 -224.5541423;-46.7152955;25.1589945;5.1583378;0.0485946;6.8916719;1.0986057 -224.7541014;-46.6281889;24.9790134;5.1678730;0.0467812;6.9234741;1.1376642 -224.9540606;-46.5393961;24.7998418;5.1770461;0.0449636;6.9562538;1.1769487 -225.1540198;-46.4490002;24.6214844;5.1858553;0.0431481;6.9900036;1.2162410 -225.3539789;-46.3570689;24.4439135;5.1943019;0.0413363;7.0247097;1.2555567 -225.5539381;-46.2636695;24.2671019;5.2023867;0.0395258;7.0603589;1.2950950 -225.7538973;-46.1688830;24.0910478;5.2101091;0.0377178;7.0969430;1.3348787 -225.9538564;-46.0727620;23.9156961;5.2174685;0.0358846;7.1344546;1.3764017 -226.1538156;-45.9753911;23.7410491;5.2244603;0.0340486;7.1729276;1.4185782 -226.3537747;-45.8768349;23.5670719;5.2310869;0.0322640;7.2123648;1.4586661 -226.5537339;-45.7771541;23.3937271;5.2373680;0.0305585;7.2526928;1.4952969 -226.7536931;-45.6764207;23.2210027;5.2433075;0.0288502;7.2938021;1.5329046 -226.9536522;-45.5746808;23.0488637;5.2490904;0.0292418;7.3357062;1.4583774 -227.1536114;-45.4719355;22.8773216;5.2550051;0.0299177;7.3753521;1.3706437 -227.3535706;-45.3681652;22.7063970;5.2610752;0.0311260;7.4124195;1.2560806 -227.5535297;-45.2633314;22.5361232;5.2675070;0.0332056;7.4462268;1.0960967 -227.7534889;-45.1573681;22.3665472;5.2743549;0.0352879;7.4756031;0.9398902 -227.9534481;-45.0502113;22.1977235;5.2816178;0.0373528;7.5007014;0.7888276 -228.1534072;-44.9417972;22.0297060;5.2892932;0.0394183;7.5217012;0.6420634 -228.3533664;-44.8320620;21.8625481;5.2973822;0.0414903;7.5387506;0.4994530 -228.5533256;-44.7209432;21.6963054;5.3058867;0.0435728;7.5519866;0.3609537 -228.7532847;-44.6083824;21.5310404;5.3148079;0.0456589;7.5615378;0.2271225 -228.9532439;-44.4943143;21.3668053;5.3241458;0.0477369;7.5675415;0.0987747 -229.1532031;-44.3786859;21.2036697;5.3338993;0.0498194;7.5701510;-0.0247117 -229.3531622;-44.2614380;21.0416939;5.3440696;0.0519024;7.5694982;-0.1430038 -229.5531214;-44.1425135;20.8809411;5.3546563;0.0539862;7.5657196;-0.2560392 -229.7530806;-44.0218654;20.7214877;5.3656601;0.0560773;7.5589496;-0.3641342 -229.9530397;-43.8994304;20.5633886;5.3770823;0.0581660;7.5493109;-0.4666709 -230.1529989;-43.7751693;20.4067300;5.3889227;0.0602640;7.5369400;-0.5642945 -230.3529580;-43.6490294;20.2515800;5.4011832;0.0623648;7.5219540;-0.6566132 -230.5529172;-43.5209608;20.0980105;5.4138641;0.0644692;7.5044787;-0.7436704 -230.7528764;-43.3909318;19.9461148;5.4269662;0.0665859;7.4846372;-0.8259687 -230.9528355;-43.2588804;19.7959506;5.4404927;0.0687017;7.4625380;-0.9027667 -231.1527947;-43.1247863;19.6476232;5.4544429;0.0708326;7.4383090;-0.9750285 -231.3527539;-42.9886048;19.5012098;5.4688204;0.0729710;7.4120516;-1.0423359 -231.5527130;-42.8502952;19.3567925;5.4836265;0.0751182;7.3838784;-1.2199705 -231.7526722;-42.7098458;19.2144830;5.4988624;0.0772845;7.3507667;-1.3866066 -231.9526314;-42.5671960;19.0743429;5.5145337;0.0794524;7.3129503;-1.3177802 -232.1525905;-42.4223495;18.9364981;5.5306394;0.0816435;7.2768288;-1.2671591 -232.3525497;-42.2752720;18.8010363;5.5471851;0.0838472;7.2419250;-1.2550322 -232.5525089;-42.1259348;18.6680511;5.5641732;0.0860656;7.2071885;-1.2430213 -232.7524680;-41.9743515;18.5376730;5.5816056;0.0883122;7.1726187;-1.2311255 -232.9524272;-41.8204632;18.4099700;5.5994905;0.0905612;7.1382148;-1.2193434 -233.1523864;-41.6643046;18.2850881;5.6178263;0.0928434;7.1039758;-1.2076741 -233.3523455;-41.5058546;18.1631267;5.6366213;0.0951494;7.0699011;-1.1961165 -233.5523047;-41.3451005;18.0441929;5.6558812;0.0974852;7.0359898;-1.1846695 -233.7522638;-41.1820854;17.9284341;5.6756091;0.0998601;7.0022412;-1.1733321 -233.9522230;-41.0167571;17.8159300;5.6958199;0.1022775;6.9686544;-1.1621031 -234.1521822;-40.8491844;17.7068449;5.7165166;0.1047447;6.9352288;-1.1509816 -234.3521413;-40.6793633;17.6012929;5.7377112;0.1072601;6.9019634;-1.1399666 -234.5521005;-40.5073034;17.4993991;5.7594172;0.1098405;6.8688577;-1.1290570 -234.7520597;-40.3330780;17.4013260;5.7816408;0.1124739;6.8359107;-1.1182517 -234.9520188;-40.1566520;17.3071753;5.8044039;0.1151939;6.8031218;-1.1075499 -235.1519780;-39.9781287;17.2171257;5.8277152;0.1179840;6.7704901;-1.0969505 -235.3519372;-39.7975297;17.1313121;5.8515912;0.1208530;6.7380150;-1.0864525 -235.5518963;-39.6148958;17.0498816;5.8760546;0.1238309;6.7056956;-1.0760550 -235.7518555;-39.4303326;16.9730107;5.9011168;0.1268810;6.6735312;-1.0657570 -235.9518147;-39.2438392;16.9008321;5.9268088;0.1300881;6.6415212;-1.0555576 -236.1517738;-39.0555563;16.8335378;5.9531496;0.1333968;6.6096646;-1.0454558 -236.3517330;-38.8655435;16.7712886;5.9801622;0.1368252;6.5779609;-1.0354506 -236.5516922;-38.6738871;16.7142578;6.0078800;0.1404158;6.5464092;-1.0255412 -236.7516513;-38.4807332;16.6626377;6.0363223;0.1441082;6.5150089;-1.0157267 -236.9516105;-38.2861312;16.6165956;6.0655315;0.1480455;6.4837592;-1.0060060 -237.1515697;-38.0902798;16.5763402;6.0955413;0.1521469;6.4526594;-0.9963784 -237.3515288;-37.8932872;16.5420597;6.1263764;0.1561789;6.4217088;-0.9868429 -237.5514880;-37.6953095;16.5139459;6.1580025;0.1601567;6.3909066;-0.9773987 -237.7514471;-37.4965768;16.4921906;6.1904343;0.1643022;6.3602521;-0.9680449 -237.9514063;-37.2971964;16.4769476;6.2233423;0.1647537;6.3297447;-0.9587805 -238.1513655;-37.0974409;16.4682815;6.2563312;0.1652345;6.2993836;-0.9496049 -238.3513246;-36.8975170;16.4662154;0.0061321;0.1635991;6.2691682;-0.9405170 -238.5512838;-36.6976230;16.4706856;0.0384582;0.1597619;6.2390977;-0.9315161 -238.7512430;-36.4979503;16.4815402;0.0700361;0.1560801;6.2091714;-0.9226014 -238.9512021;-36.2987509;16.4986079;0.1007429;0.1511028;6.1793887;-0.9137720 -239.1511613;-36.1001273;16.5216893;0.1304713;0.1462543;6.1497488;-0.9050271 -239.3511205;-35.9022729;16.5505680;0.1592435;0.1415406;6.1202511;-0.8963658 -239.5510796;-35.7053210;16.5850332;0.1870797;0.1369043;6.0908949;-0.8963658 -239.7510388;-35.5093556;16.6248832;0.2140034;0.1323790;6.0613965;-0.7820779 -239.9509980;-35.3145604;16.6698957;0.2400295;0.1279789;6.0355414;-0.5599027 -240.1509571;-35.1209457;16.7198868;0.2651878;0.1236575;6.0169631;-0.3600946 -240.3509163;-34.9286386;16.7746466;0.2894903;0.1194358;6.0049843;-0.1805853 -240.5508755;-34.7376988;16.8339816;0.3129549;0.1152782;5.9989680;-0.0175838 -240.7508346;-34.5481459;16.8977128;0.3355987;0.1111916;5.9983818;0.1307287 -240.9507938;-34.3601051;16.9656252;0.3574283;0.1071848;6.0027382;0.2658486 -241.1507530;-34.1735267;17.0375659;0.3784654;0.1032260;6.0115874;0.3905293 -241.3507121;-33.9884868;17.1133368;0.3987158;0.0993348;6.0245633;0.5053755 -241.5506713;-33.8049918;17.1927664;0.4181928;0.0954880;6.0413137;0.6124409 -241.7506304;-33.6230171;17.2756988;0.4369077;0.0916856;6.0615508;0.7127264 -241.9505896;-33.4426390;17.3619317;0.4548632;0.0879328;6.0850169;0.8069307 -242.1505488;-33.2637708;17.4513397;0.4720743;0.0842089;6.1114758;0.8966147 -242.3505079;-33.0864470;17.5437399;0.4885436;0.0805271;6.1407418;0.9819577 -242.5504671;-32.9106363;17.6389819;0.5042794;0.0768724;6.1726342;1.0641509 -242.7504263;-32.7362854;17.7369294;0.5192892;0.0732444;6.2070110;1.1437396 -242.9503854;-32.5634256;17.8373978;0.5335735;0.0696453;6.2437479;1.2211283 -243.1503446;-32.3919537;17.9402805;0.5471420;0.0660631;6.2827335;1.2972226 -243.3503038;-32.2218667;18.0454126;0.5599951;0.0624957;6.3238851;1.3725040 -243.5502629;-32.0531085;18.1526609;0.5721354;0.0589367;6.3671353;1.4475969 -243.7502221;-31.8856079;18.2619024;0.5835667;0.0553913;6.4124358;1.5226239 -243.9501813;-31.7193540;18.3729746;0.5942873;0.0518457;6.4597413;1.5984831 -244.1501404;-31.5542417;18.4857773;0.6043009;0.0483090;6.5090338;1.6750888 -244.3500996;-31.3902334;18.6001651;0.6136077;0.0447775;6.5602911;1.7528981 -244.5500588;-31.2272574;18.7160156;0.6222084;0.0412484;6.6135040;1.8323233 -244.7500179;-31.0652320;18.8332140;0.6301045;0.0377257;6.6686742;1.9134661 -244.9499771;-30.9041094;18.9516210;0.6372956;0.0342025;6.7258045;1.9969209 -245.1499363;-30.7437915;19.0711338;0.6437829;0.0306831;6.7849135;2.0827727 -245.3498954;-30.5842119;19.1916264;0.6495666;0.0271652;6.8460200;2.1714112 -245.5498546;-30.4252904;19.3129831;0.6546468;0.0236478;6.9091517;2.2631852 -245.7498137;-30.2669419;19.4350920;0.6590240;0.0201323;6.9743434;2.3583164 -245.9497729;-30.1090877;19.5578361;0.6626980;0.0166157;7.0416333;2.4572640 -246.1497321;-29.9516433;19.6811033;0.6656690;0.0130999;7.1110692;2.5602608 -246.3496912;-29.7945198;19.8047844;0.6679369;0.0095835;7.1827015;2.6677070 -246.5496504;-29.6376346;19.9287655;0.6695016;0.0060663;7.2565877;2.7799724 -246.7496096;-29.4809043;20.0529335;0.6703629;0.0025485;7.3327912;2.8974142 -246.9495687;-29.3242279;20.1771887;0.6705206;-0.0009712;7.4113802;2.9138115 -247.1495279;-29.1675367;20.3014060;0.6699745;-0.0044919;7.4895823;2.6479305 -247.3494871;-29.0107279;20.4254875;0.6687241;-0.0080150;7.5599470;2.3810545 -247.5494462;-28.8537213;20.5493167;0.6667689;-0.0115403;7.6226653;2.1142186 -247.7494054;-28.6964391;20.6727757;0.6641089;-0.0150676;7.6779256;1.8484657 -247.9493646;-28.5387679;20.7957740;0.6607428;-0.0185989;7.7259159;1.5846849 -248.1493237;-28.3806561;20.9181729;0.6566706;-0.0221328;7.7668218;1.3239579 -248.3492829;-28.2219954;21.0398776;0.6518911;-0.0256721;7.8008330;1.0670637 -248.5492421;-28.0627128;21.1607656;0.6464034;-0.0292166;7.8281373;0.8149404 -248.7492012;-27.9027394;21.2807114;0.6402070;-0.0327637;7.8489263;0.5686265 -248.9491604;-27.7419615;21.3996230;0.6333001;-0.0363159;7.8633993;0.3287984 -249.1491196;-27.5803433;21.5173500;0.6256831;-0.0398730;7.8717559;0.0962543 -249.3490787;-27.4177809;21.6337925;0.6173528;-0.0434542;7.8742005;-0.1294751 -249.5490379;-27.2542140;21.7488171;0.6083036;-0.0470550;7.8709119;-0.3474067 -249.7489970;-27.0895876;21.8622870;0.5985352;-0.0506259;7.8620812;-0.5538235 -249.9489562;-26.9238009;21.9740997;0.5880802;-0.0539415;7.8479829;-0.7344150 -250.1489154;-26.7568323;22.0841082;0.5769629;-0.0572570;7.8292484;-0.9053389 -250.3488745;-26.5886171;22.1922034;0.5653168;-0.0584321;7.8060918;-0.9358886 -250.5488337;-26.4191471;22.2983294;0.5536429;-0.0583310;7.7820813;-0.8868489 -250.7487929;-26.2484495;22.4024724;0.5419903;-0.0581317;7.7592604;-0.8341796 -250.9487520;-26.0765579;22.5046251;0.5304528;-0.0572695;7.7377334;-0.7443418 -251.1487112;-25.9035028;22.6048056;0.5190866;-0.0564165;7.7184741;-0.6596538 -251.3486704;-25.7293313;22.7030258;0.5078859;-0.0556393;7.7013658;-0.5837502 -251.5486295;-25.5540777;22.7993021;0.4968338;-0.0549058;7.6861943;-0.5141977 -251.7485887;-25.3777748;22.8936501;0.4859276;-0.0541792;7.6728056;-0.4484693 -251.9485479;-25.2004658;22.9860797;0.4751657;-0.0534646;7.6611092;-0.3866312 -252.1485070;-25.0221729;23.0766114;0.4645458;-0.0527558;7.6510113;-0.3280883 -252.3484662;-24.8429389;23.1652552;0.4540666;-0.0520629;7.6424319;-0.2732325 -252.5484254;-24.6627909;23.2520289;0.4437245;-0.0513802;7.6352796;-0.2215294 -252.7483845;-24.4817566;23.3369491;0.4335181;-0.0507039;7.6294758;-0.1725703 -252.9483437;-24.2998786;23.4200259;0.4234463;-0.0500377;7.6249516;-0.1264052 -253.1483029;-24.1171709;23.5012821;0.4135069;-0.0493763;7.6216360;-0.0825748 -253.3482620;-23.9336748;23.5807283;0.4036995;-0.0487194;7.6194693;-0.0409295 -253.5482212;-23.7494122;23.6583837;0.3940230;-0.0480667;7.6183951;-0.0013163 -253.7481803;-23.5644071;23.7342664;0.3844763;-0.0474187;7.6183605;0.0363501 -253.9481395;-23.3786996;23.8083880;0.3750592;-0.0467742;7.6193145;0.0722467 -254.1480987;-23.1922987;23.8807727;0.3657702;-0.0461337;7.6212103;0.1064538 -254.3480578;-23.0052436;23.9514327;0.3566092;-0.0454965;7.6240029;0.1391000 -254.5480170;-22.8175518;24.0203887;0.3475752;-0.0448627;7.6276502;0.1702785 -254.7479762;-22.6292441;24.0876599;0.3386674;-0.0442327;7.6321128;0.2000447 -254.9479353;-22.4403579;24.1532598;0.3298857;-0.0436050;7.6373521;0.2285672 -255.1478945;-22.2508983;24.2172131;0.3212288;-0.0429806;7.6433341;0.2558549 -255.3478537;-22.0609020;24.2795339;0.3126967;-0.0423590;7.6500246;0.2820198 -255.5478128;-21.8703829;24.3402437;0.3042886;-0.0417400;7.6573926;0.3071304 -255.7477720;-21.6793591;24.3993628;0.2960037;-0.0411240;7.6654086;0.3312211 -255.9477312;-21.4878644;24.4569064;0.2878423;-0.0405098;7.6740439;0.3544278 -256.1476903;-21.2959015;24.5128994;0.2798030;-0.0398984;7.6832735;0.3767380 -256.3476495;-21.1035038;24.5673575;0.2718860;-0.0392890;7.6930720;0.3982521 -256.5476087;-20.9106825;24.6203029;0.2640905;-0.0386817;7.7034164;0.4190148 -256.7475678;-20.7174531;24.6717564;0.2564161;-0.0380768;7.7142852;0.4390451 -256.9475270;-20.5238457;24.7217351;0.2488629;-0.0374732;7.7256572;0.4584563 -257.1474862;-20.3298614;24.7702637;0.2414298;-0.0368720;7.7375141;0.4772244 -257.3474453;-20.1355301;24.8173594;0.2341169;-0.0362722;7.7498371;0.4954354 -257.5474045;-19.9408607;24.8630448;0.2269238;-0.0356741;7.7626096;0.5131183 -257.7473636;-19.7458664;24.9073412;0.2198499;-0.0350779;7.7758160;0.5302835 -257.9473228;-19.5505736;24.9502672;0.2128955;-0.0344827;7.7894405;0.5470260 -258.1472820;-19.3549824;24.9918472;0.2060596;-0.0338893;7.8034704;0.5633162 -258.3472411;-19.1591189;25.0320998;0.1993424;-0.0332970;7.8178917;0.5792280 -258.5472003;-18.9629902;25.0710477;0.1927435;-0.0327059;7.8326926;0.5947793 -258.7471595;-18.7666077;25.1087127;0.1862625;-0.0321164;7.8478619;0.6099755 -258.9471186;-18.5699935;25.1451147;0.1798996;-0.0315275;7.8633884;0.6248969 -259.1470778;-18.3731479;25.1802775;0.1736540;-0.0309401;7.8792630;0.6395116 -259.3470370;-18.1760926;25.2142211;0.1675260;-0.0303534;7.8954758;0.6538834 -259.5469961;-17.9788337;25.2469683;0.1615151;-0.0297677;7.9120186;0.6680227 -259.7469553;-17.7813806;25.2785412;0.1556211;-0.0291832;7.9288834;0.6819319 -259.9469145;-17.5837517;25.3089605;0.1498442;-0.0285990;7.9460625;0.6956794 -260.1468736;-17.3859473;25.3382499;0.1441838;-0.0280159;7.9635497;0.7092328 -260.3468328;-17.1879852;25.3664303;0.1386400;-0.0274334;7.9813382;0.7226481 -260.5467920;-16.9898706;25.3935244;0.1332127;-0.0268515;7.9994225;0.0231058 -260.7467511;-16.7916112;25.4195547;0.1279015;-0.0262705;8.0000000;0.0000000 -260.9467103;-16.5932217;25.4445427;0.1227066;-0.0256896;8.0000000;0.0000000 -261.1466695;-16.3947028;25.4685117;0.1176277;-0.0251096;8.0000000;0.0000000 -261.3466286;-16.1960685;25.4914834;0.1126648;-0.0245299;8.0000000;0.0000000 -261.5465878;-15.9973232;25.5134806;0.1078177;-0.0239506;8.0000000;0.0000000 -261.7465469;-15.7984734;25.5345258;0.1030864;-0.0233720;8.0000000;0.0000000 -261.9465061;-15.5995301;25.5546413;0.0984709;-0.0227933;8.0000000;0.0000000 -262.1464653;-15.4004947;25.5738501;0.0939709;-0.0222152;8.0000000;0.0000000 -262.3464244;-15.2013775;25.5921743;0.0895866;-0.0216373;8.0000000;0.0000000 -262.5463836;-15.0021825;25.6096370;0.0853177;-0.0210596;8.0000000;0.0000000 -262.7463428;-14.8029148;25.6262607;0.0811644;-0.0204823;8.0000000;0.0000000 -262.9463019;-14.6035822;25.6420681;0.0771265;-0.0199049;8.0000000;0.0000000 -263.1462611;-14.4041870;25.6570821;0.0732040;-0.0193279;8.0000000;0.0000000 -263.3462203;-14.2047360;25.6713252;0.0693969;-0.0187509;8.0000000;0.0000000 -263.5461794;-14.0052328;25.6848205;0.0657052;-0.0181740;8.0000000;0.0000000 -263.7461386;-13.8056816;25.6975907;0.0621288;-0.0175973;8.0000000;0.0000000 -263.9460978;-13.6060870;25.7096586;0.0586677;-0.0170203;8.0000000;0.0000000 -264.1460569;-13.4064525;25.7210472;0.0553220;-0.0164436;8.0000000;0.0000000 -264.3460161;-13.2067813;25.7317793;0.0520916;-0.0158668;8.0000000;0.0000000 -264.5459753;-13.0070774;25.7418778;0.0489766;-0.0152901;8.0000000;0.0000000 -264.7459344;-12.8073436;25.7513657;0.0459768;-0.0147135;8.0000000;0.0000000 -264.9458936;-12.6075822;25.7602660;0.0430924;-0.0141366;8.0000000;0.0000000 -265.1458527;-12.4077973;25.7686015;0.0403233;-0.0135598;8.0000000;0.0000000 -265.3458119;-12.2079896;25.7763954;0.0376696;-0.0129827;8.0000000;0.0000000 -265.5457711;-12.0081627;25.7836704;0.0351313;-0.0124056;8.0000000;0.0000000 -265.7457302;-11.8083191;25.7904498;0.0327084;-0.0118286;8.0000000;0.0000000 -265.9456894;-11.6084585;25.7967565;0.0304008;-0.0112514;8.0000000;0.0000000 -266.1456486;-11.4085860;25.8026134;0.0282087;-0.0106744;8.0000000;0.0000000 -266.3456077;-11.2086998;25.8080438;0.0261320;-0.0100968;8.0000000;0.0000000 -266.5455669;-11.0088037;25.8130706;0.0241708;-0.0095191;8.0000000;0.0000000 -266.7455261;-10.8088995;25.8177169;0.0223251;-0.0089413;8.0000000;0.0000000 -266.9454852;-10.6089849;25.8220058;0.0205950;-0.0083633;8.0000000;0.0000000 -267.1454444;-10.4090661;25.8259604;0.0189805;-0.0077853;8.0000000;0.0000000 -267.3454036;-10.2091391;25.8296037;0.0174815;-0.0072070;8.0000000;0.0000000 -267.5453627;-10.0092080;25.8329589;0.0160983;-0.0066285;8.0000000;0.0000000 -267.7453219;-9.8092739;25.8360491;0.0148307;-0.0060498;8.0000000;0.0000000 -267.9452811;-9.6093333;25.8388975;0.0136789;-0.0054709;8.0000000;0.0000000 -268.1452402;-9.4093930;25.8415271;0.0126428;-0.0048919;8.0000000;0.0000000 -268.3451994;-9.2094474;25.8439612;0.0117225;-0.0043124;8.0000000;0.0000000 -268.5451586;-9.0095009;25.8462228;0.0109182;-0.0037326;8.0000000;0.0000000 -268.7451177;-8.8095543;25.8483352;0.0102298;-0.0031523;8.0000000;0.0000000 -268.9450769;-8.6096031;25.8503216;0.0096577;-0.0025699;8.0000000;0.0000000 -269.1450360;-8.4096546;25.8522052;0.0092021;-0.0019874;8.0000000;0.0000000 -269.3449952;-8.2097021;25.8540094;0.0088636;-0.0013960;8.0000000;0.0000000 -269.5449544;-8.0097505;25.8557578;0.0086439;-0.0008013;8.0000000;0.0000000 -269.7449135;-7.8098001;25.8574742;0.0085433;-0.0002002;8.0000000;0.0000000 -269.9448727;-7.6098458;25.8591826;0.0085654;0.0004219;8.0000000;0.0000000 -270.1448319;-7.4098963;25.8609079;0.0087120;0.0010442;8.0000000;0.0000000 -270.3447910;-7.2099434;25.8626747;0.0089777;0.0015933;8.0000000;0.0000000 -270.5447502;-7.0099927;25.8645052;0.0093485;0.0021157;8.0000000;0.0000000 -270.7447094;-6.8100449;25.8664202;0.0098223;0.0025733;8.0000000;0.0000000 -270.9446685;-6.6100948;25.8684373;0.0103614;0.0028188;8.0000000;0.0000000 -271.1446277;-6.4101482;25.8705671;0.0109495;0.0030642;8.0000000;0.0000000 -271.3445869;-6.2102021;25.8728189;0.0115754;0.0031557;8.0000000;0.0000000 -271.5445460;-6.0102572;25.8751968;0.0122101;0.0031920;8.0000000;0.0000000 -271.7445052;-5.8103140;25.8777023;0.0128514;0.0032046;8.0000000;0.0000000 -271.9444644;-5.6103725;25.8803356;0.0134859;0.0031418;8.0000000;0.0000000 -272.1444235;-5.4104321;25.8830945;0.0141079;0.0030790;8.0000000;0.0000000 -272.3443827;-5.2104939;25.8859766;0.0147174;0.0030177;8.0000000;0.0000000 -272.5443419;-5.0105573;25.8889793;0.0153147;0.0029570;8.0000000;0.0000000 -272.7443010;-4.8106223;25.8921002;0.0159000;0.0028967;8.0000000;0.0000000 -272.9442602;-4.6106897;25.8953369;0.0164733;0.0028378;8.0000000;0.0000000 -273.1442193;-4.4107582;25.8986871;0.0170348;0.0027789;8.0000000;0.0000000 -273.3441785;-4.2108293;25.9021483;0.0175843;0.0027158;8.0000000;0.0000000 -273.5441377;-4.0109020;25.9057182;0.0181209;0.0026513;8.0000000;0.0000000 -273.7440968;-3.8109763;25.9093940;0.0186445;0.0025836;8.0000000;0.0000000 -273.9440560;-3.6110532;25.9131730;0.0191534;0.0025061;8.0000000;0.0000000 -274.1440152;-3.4111313;25.9170523;0.0196468;0.0024286;8.0000000;0.0000000 -274.3439743;-3.2112120;25.9210286;0.0201246;0.0023504;8.0000000;0.0000000 -274.5439335;-3.0112942;25.9250989;0.0205868;0.0022720;8.0000000;0.0000000 -274.7438927;-2.8113781;25.9292600;0.0210332;0.0021938;8.0000000;0.0000000 -274.9438518;-2.6114644;25.9335088;0.0214641;0.0021161;8.0000000;0.0000000 -275.1438110;-2.4115519;25.9378423;0.0218795;0.0020384;8.0000000;0.0000000 -275.3437702;-2.2116417;25.9422571;0.0222794;0.0019618;8.0000000;0.0000000 -275.5437293;-2.0117330;25.9467505;0.0226641;0.0018854;8.0000000;0.0000000 -275.7436885;-1.8118258;25.9513191;0.0230334;0.0018087;8.0000000;0.0000000 -275.9436477;-1.6119209;25.9559601;0.0233873;0.0017306;8.0000000;0.0000000 -276.1436068;-1.4120169;25.9606703;0.0237255;0.0016526;8.0000000;0.0000000 -276.3435660;-1.2121150;25.9654464;0.0240478;0.0015690;8.0000000;0.0000000 -276.5435252;-1.0122144;25.9702853;0.0243530;0.0014836;8.0000000;0.0000000 -276.7434843;-0.8123150;25.9751835;0.0246411;0.0013981;8.0000000;0.0000000 -276.9434435;-0.6124175;25.9801376;0.0249121;0.0013122;8.0000000;0.0000000 -277.1434026;-0.4125207;25.9851442;0.0251659;0.0012264;8.0000000;0.0000000 -277.3433618;-0.2126257;25.9901997;0.0254026;0.0011411;8.0000000;0.0000000 -277.5433210;-0.0127316;25.9953009;0.0256222;0.0010561;8.0000000;0.0000000 -277.7432801;0.1871616;26.0004443;0.0258249;0.0009714;8.0000000;0.0000000 -277.9432393;0.3870533;26.0056265;0.0260108;0.0008876;8.0000000;0.0000000 -278.1431985;0.5869447;26.0108442;0.0261799;0.0008037;8.0000000;0.0000000 -278.3431576;0.7868347;26.0160940;0.0263323;0.0007208;8.0000000;0.0000000 -278.5431168;0.9867242;26.0213726;0.0264681;0.0006381;8.0000000;0.0000000 -278.7430760;1.1866132;26.0266768;0.0265875;0.0005555;8.0000000;0.0000000 -278.9430351;1.3865012;26.0320031;0.0266903;0.0004735;8.0000000;0.0000000 -279.1429943;1.5863892;26.0373484;0.0267768;0.0003914;8.0000000;0.0000000 -279.3429535;1.7862762;26.0427093;0.0268470;0.0003105;8.0000000;0.0000000 -279.5429126;1.9861632;26.0480826;0.0269010;0.0002298;8.0000000;0.0000000 -279.7428718;2.1860501;26.0534651;0.0269389;0.0001498;8.0000000;0.0000000 -279.9428310;2.3859364;26.0588536;0.0269610;0.0000712;8.0000000;0.0000000 -280.1427901;2.5858231;26.0642450;0.0269674;-0.0000074;8.0000000;0.0000000 -280.3427493;2.7857094;26.0696360;0.0269581;-0.0000850;8.0000000;0.0000000 -280.5427085;2.9855960;26.0750237;0.0269333;-0.0001624;8.0000000;0.0000000 -280.7426676;3.1854829;26.0804049;0.0268932;-0.0002395;8.0000000;0.0000000 -280.9426268;3.3853697;26.0857764;0.0268376;-0.0003162;8.0000000;0.0000000 -281.1425859;3.5852573;26.0911354;0.0267667;-0.0003929;8.0000000;0.0000000 -281.3425451;3.7851448;26.0964787;0.0266806;-0.0004680;8.0000000;0.0000000 -281.5425043;3.9850331;26.1018032;0.0265796;-0.0005427;8.0000000;0.0000000 -281.7424634;4.1849221;26.1071061;0.0264636;-0.0006167;8.0000000;0.0000000 -281.9424226;4.3848114;26.1123843;0.0263330;-0.0006891;8.0000000;0.0000000 -282.1423818;4.5847019;26.1176350;0.0261880;-0.0007615;8.0000000;0.0000000 -282.3423409;4.7845927;26.1228552;0.0260285;-0.0008342;8.0000000;0.0000000 -282.5423001;4.9844846;26.1280421;0.0258544;-0.0009070;8.0000000;0.0000000 -282.7422593;5.1843775;26.1331927;0.0256627;-0.0010850;8.0000000;0.0000000 -282.9422184;5.3842712;26.1382990;0.0254016;-0.0015265;8.0000000;0.0000000 -283.1421776;5.5841670;26.1433443;0.0250523;-0.0019679;8.0000000;0.0000000 -283.3421368;5.7840626;26.1483078;0.0245565;-0.0031479;8.0000000;0.0000000 -283.5420959;5.9839628;26.1531455;0.0237892;-0.0045271;8.0000000;0.0000000 -283.7420551;6.1838679;26.1578024;0.0227497;-0.0057788;8.0000000;0.0000000 -283.9420143;6.3837745;26.1622292;0.0215003;-0.0067183;8.0000000;0.0000000 -284.1419734;6.5836944;26.1663876;0.0200630;-0.0076575;8.0000000;0.0000000 -284.3419326;6.7836134;26.1702381;0.0184085;-0.0089680;8.0000000;0.0000000 -284.5418918;6.9835427;26.1737303;0.0164745;-0.0103766;8.0000000;0.0000000 -284.7418509;7.1834810;26.1768076;0.0142578;-0.0118166;8.0000000;0.0000000 -284.9418101;7.3834212;26.1794121;0.0117434;-0.0133329;8.0000000;0.0000000 -285.1417692;7.5833720;26.1814836;0.0089257;-0.0148492;8.0000000;0.0000000 -285.3417284;7.7833246;26.1829615;0.0058060;-0.0163517;8.0000000;0.0000000 -285.5416876;7.9832822;26.1837856;0.0023864;-0.0178508;8.0000000;0.0000000 -285.7416467;8.1832423;26.1838959;6.2818525;-0.0193466;8.0000000;0.0000000 -285.9416059;8.3831995;26.1832327;6.2778352;-0.0208345;8.0000000;0.0000000 -286.1415651;8.5831539;26.1817365;6.2735204;-0.0223228;8.0000000;0.0000000 -286.3415242;8.7830986;26.1793478;6.2689085;-0.0238038;8.0000000;0.0000000 -286.5414834;8.9830298;26.1760075;6.2640008;-0.0252836;8.0000000;0.0000000 -286.7414426;9.1829419;26.1716564;6.2587971;-0.0267634;8.0000000;0.0000000 -286.9414017;9.3828277;26.1662355;6.2532976;-0.0282427;8.0000000;0.0000000 -287.1413609;9.5826790;26.1596859;6.2475022;-0.0297233;8.0000000;0.0000000 -287.3413201;9.7824893;26.1519486;6.2414110;-0.0312013;8.0000000;0.0000000 -287.5412792;9.9822462;26.1429648;6.2350241;-0.0326804;8.0000000;0.0000000 -287.7412384;10.1819398;26.1326759;6.2283414;-0.0341596;8.0000000;0.0000000 -287.9411976;10.3815605;26.1210231;6.2213630;-0.0356382;8.0000000;0.0000000 -288.1411567;10.5810894;26.1079484;6.2140889;-0.0371192;8.0000000;0.0000000 -288.3411159;10.7805202;26.0933927;6.2065186;-0.0385983;8.0000000;0.0000000 -288.5410751;10.9798299;26.0772985;6.1986524;-0.0400798;8.0000000;0.0000000 -288.7410342;11.1790033;26.0596075;6.1904898;-0.0415623;8.0000000;0.0000000 -288.9409934;11.3780270;26.0402615;6.1820308;-0.0430452;8.0000000;0.0000000 -289.1409525;11.5768699;26.0192038;6.1732750;-0.0445320;8.0000000;0.0000000 -289.3409117;11.7755252;25.9963756;6.1642217;-0.0460178;8.0000000;0.0000000 -289.5408709;11.9739575;25.9717208;6.1548712;-0.0475077;8.0000000;0.0000000 -289.7408300;12.1721449;25.9451825;6.1452224;-0.0490003;8.0000000;0.0000000 -289.9407892;12.3700694;25.9167026;6.1352748;-0.0504951;8.0000000;0.0000000 -290.1407484;12.5676860;25.8862273;6.1250282;-0.0519959;8.0000000;0.0000000 -290.3407075;12.7649862;25.8536972;6.1144807;-0.0534979;8.0000000;0.0000000 -290.5406667;12.9619210;25.8190595;6.1036326;-0.0550067;8.0000000;0.0000000 -290.7406259;13.1584604;25.7822583;6.0924823;-0.0565205;8.0000000;0.0000000 -290.9405850;13.3545800;25.7432365;6.0810285;-0.0580390;8.0000000;0.0000000 -291.1405442;13.5502205;25.7019440;6.0692709;-0.0595663;8.0000000;0.0000000 -291.3405034;13.7453692;25.6583211;6.0572067;-0.0610972;8.0000000;0.0000000 -291.5404625;13.9399628;25.6123192;6.0448359;-0.0626383;8.0000000;0.0000000 -291.7404217;14.1339621;25.5638844;6.0321562;-0.0641874;8.0000000;0.0000000 -291.9403809;14.3273340;25.5129609;6.0191653;-0.0657458;8.0000000;0.0000000 -292.1403400;14.5200044;25.4595040;6.0058626;-0.0673166;8.0000000;0.0000000 -292.3402992;14.7119539;25.4034538;5.9922439;-0.0688944;8.0000000;0.0000000 -292.5402584;14.9031043;25.3447673;5.9783090;-0.0704863;8.0000000;0.0000000 -292.7402175;15.0934055;25.2833935;5.9640547;-0.0720908;8.0000000;0.0000000 -292.9401767;15.2828131;25.2192793;5.9494772;-0.0737117;8.0000000;0.0000000 -293.1401358;15.4712391;25.1523860;5.9345751;-0.0753490;8.0000000;0.0000000 -293.3400950;15.6586526;25.0826552;5.9193431;-0.0769987;8.0000000;0.0000000 -293.5400542;15.8449613;25.0100507;5.9037800;-0.0786679;8.0000000;0.0000000 -293.7400133;16.0301019;24.9345257;5.8878816;-0.0803563;8.0000000;0.0000000 -293.9399725;16.2140151;24.8560314;5.8716421;-0.0820699;8.0000000;0.0000000 -294.1399317;16.3966009;24.7745362;5.8550591;-0.0838047;8.0000000;0.0000000 -294.3398908;16.5778100;24.6899860;5.8381256;-0.0855643;8.0000000;0.0000000 -294.5398500;16.7575384;24.6023515;5.8208382;-0.0873509;8.0000000;0.0000000 -294.7398092;16.9357067;24.5115923;5.8031911;-0.0891694;8.0000000;0.0000000 -294.9397683;17.1122360;24.4176668;5.7851743;-0.0910358;8.0000000;0.0000000 -295.1397275;17.2870155;24.3205495;5.7667825;-0.0929311;8.0000000;0.0000000 -295.3396867;17.4599706;24.2201954;5.7480101;-0.0948284;8.0000000;0.0000000 -295.5396458;17.6309864;24.1165831;5.7288563;-0.0967555;8.0000000;0.0000000 -295.7396050;17.7999626;24.0096838;5.7093200;-0.0985581;8.0000000;0.0000000 -295.9395642;17.9668029;23.8994740;5.6894574;-0.1001147;8.0000000;0.0000000 -296.1395233;18.1314049;23.7859455;5.6692806;-0.1016977;8.0000000;0.0000000 -296.3394825;18.2936624;23.6691090;5.6489843;-0.1010102;8.0000000;0.0000000 -296.5394416;18.4535365;23.5490123;5.6288882;-0.0999966;8.0000000;0.0000000 -296.7394008;18.6109779;23.4257427;5.6089990;-0.0988016;8.0000000;0.0000000 -296.9393600;18.7659469;23.2993934;5.5893974;-0.0972677;8.0000000;0.0000000 -297.1393191;18.9184438;23.1700416;5.5700969;-0.0957720;8.0000000;0.0000000 -297.3392783;19.0684184;23.0378085;5.5510950;-0.0942990;8.0000000;0.0000000 -297.5392375;19.2158833;22.9027618;5.5323838;-0.0928545;8.0000000;0.0000000 -297.7391966;19.3608160;22.7649999;5.5139573;-0.0914598;8.0000000;0.0000000 -297.9391558;19.5031974;22.6246181;5.4958043;-0.0901196;8.0000000;0.0000000 -298.1391150;19.6430408;22.4816782;5.4779143;-0.0888098;8.0000000;0.0000000 -298.3390741;19.7803059;22.3362965;5.4602849;-0.0875365;8.0000000;0.0000000 -298.5390333;19.9150160;22.1885228;5.4429061;-0.0862887;8.0000000;0.0000000 -298.7389925;20.0471567;22.0384463;5.4257739;-0.0850716;8.0000000;0.0000000 -298.9389516;20.1767182;21.8861525;5.4088828;-0.0838843;8.0000000;0.0000000 -299.1389108;20.3037211;21.7316897;5.3922248;-0.0827225;8.0000000;0.0000000 -299.3388700;20.4281353;21.5751679;5.3757990;-0.0815816;8.0000000;0.0000000 -299.5388291;20.5499890;21.4166253;5.3595981;-0.0804623;8.0000000;0.0000000 -299.7387883;20.6692764;21.2561424;5.3436185;-0.0793679;8.0000000;0.0000000 -299.9387475;20.7859958;21.0937952;5.3278563;-0.0782945;8.0000000;0.0000000 -300.1387066;20.9001707;20.9296241;5.3123053;-0.0772411;8.0000000;0.0000000 -300.3386658;21.0117829;20.7637291;5.2969649;-0.0762050;8.0000000;0.0000000 -300.5386249;21.1208622;20.5961407;5.2818289;-0.0751873;8.0000000;0.0000000 -300.7385841;21.2274100;20.4269307;5.2668944;-0.0741870;8.0000000;0.0000000 -300.9385433;21.3314313;20.2561664;5.2521593;-0.0732001;8.0000000;0.0000000 -301.1385024;21.4329499;20.0838846;5.2376187;-0.0722319;8.0000000;0.0000000 -301.3384616;21.5319606;19.9101703;5.2232720;-0.0712711;8.0000000;0.0000000 -301.5384208;21.6284906;19.7350537;5.2091156;-0.0703232;8.0000000;0.0000000 -301.7383799;21.7225488;19.5585966;5.1951473;-0.0693865;8.0000000;0.0000000 -301.9383391;21.8141468;19.3808572;5.1813662;-0.0684577;8.0000000;0.0000000 -302.1382983;21.9033085;19.2018701;5.1677685;-0.0675441;8.0000000;0.0000000 -302.3382574;21.9900392;19.0217064;5.1543539;-0.0666334;8.0000000;0.0000000 -302.5382166;22.0743646;18.8403974;5.1411199;-0.0657348;8.0000000;0.0000000 -302.7381758;22.1562996;18.6579952;5.1280642;-0.0648491;8.0000000;0.0000000 -302.9381349;22.2358610;18.4745496;5.1151850;-0.0639724;8.0000000;0.0000000 -303.1380941;22.3130716;18.2900957;5.1024796;-0.0631070;8.0000000;0.0000000 -303.3380533;22.3879462;18.1046878;5.0899469;-0.0622482;8.0000000;0.0000000 -303.5380124;22.4605084;17.9183594;5.0775848;-0.0613999;8.0000000;0.0000000 -303.7379716;22.5307777;17.7311535;5.0653914;-0.0605551;8.0000000;0.0000000 -303.9379308;22.5987747;17.5431119;5.0533677;-0.0597080;8.0000000;0.0000000 -304.1378899;22.6645218;17.3542717;5.0415123;-0.0588711;8.0000000;0.0000000 -304.3378491;22.7280417;17.1646689;5.0298188;-0.0580933;8.0000000;0.0000000 -304.5378082;22.7893541;16.9743430;5.0182790;-0.0573296;8.0000000;0.0000000 -304.7377674;22.8484804;16.7833274;5.0068845;-0.0567373;8.0000000;0.0000000 -304.9377266;22.9054355;16.5916523;4.9955741;-0.0563912;8.0000000;0.0000000 -305.1376857;22.9602255;16.3993478;4.9843324;-0.0560491;8.0000000;0.0000000 -305.3376449;23.0128480;16.2064398;4.9730085;-0.0573801;8.0000000;0.0000000 -305.5376041;23.0632540;16.0129392;4.9613829;-0.0589002;8.0000000;0.0000000 -305.7375632;23.1113775;15.8188577;4.9494445;-0.0606334;8.0000000;0.0000000 -305.9375224;23.1571435;15.6242077;4.9371151;-0.0626880;8.0000000;0.0000000 -306.1374816;23.2004661;15.4289986;4.9243736;-0.0647539;8.0000000;0.0000000 -306.3374407;23.2412576;15.2332438;4.9112161;-0.0668513;8.0000000;0.0000000 -306.5373999;23.2794284;15.0369634;4.8976374;-0.0689662;8.0000000;0.0000000 -306.7373591;23.3148889;14.8401745;4.8836347;-0.0710861;8.0000000;0.0000000 -306.9373182;23.3475489;14.6428998;4.8692079;-0.0732127;8.0000000;0.0000000 -307.1372774;23.3773164;14.4451747;4.8543546;-0.0753563;8.0000000;0.0000000 -307.3372366;23.4041026;14.2470140;4.8390706;-0.0775139;8.0000000;0.0000000 -307.5371957;23.4278133;14.0484688;4.8233535;-0.0796933;8.0000000;0.0000000 -307.7371549;23.4483573;13.8495704;4.8071988;-0.0818891;8.0000000;0.0000000 -307.9371141;23.4656421;13.6503574;4.7906025;-0.0841083;8.0000000;0.0000000 -308.1370732;23.4795733;13.4508942;4.7735609;-0.0863533;8.0000000;0.0000000 -308.3370324;23.4900592;13.2512036;4.7560668;-0.0886210;8.0000000;0.0000000 -308.5369915;23.4970045;13.0513699;4.7381170;-0.0909207;8.0000000;0.0000000 -308.7369507;23.5003157;12.8514424;4.7197045;-0.0932469;8.0000000;0.0000000 -308.9369099;23.4998986;12.6514806;4.7008228;-0.0956096;8.0000000;0.0000000 -309.1368690;23.4956592;12.4515802;4.6814666;-0.0980080;8.0000000;0.0000000 -309.3368282;23.4875023;12.2517798;4.6616252;-0.1004438;8.0000000;0.0000000 -309.5367874;23.4753351;12.0521973;4.6412934;-0.1029251;8.0000000;0.0000000 -309.7367465;23.4590630;11.8529073;4.6204615;-0.1054462;8.0000000;0.0000000 -309.9367057;23.4385917;11.6539961;4.5991193;-0.1080215;8.0000000;0.0000000 -310.1366649;23.4138312;11.4555917;4.5772590;-0.1106459;8.0000000;0.0000000 -310.3366240;23.3846841;11.2577615;4.5548663;-0.1133270;8.0000000;0.0000000 -310.5365832;23.3510639;11.0606563;4.5319323;-0.1160722;8.0000000;0.0000000 -310.7365424;23.3128784;10.8643850;4.5084439;-0.1188769;8.0000000;0.0000000 -310.9365015;23.2700367;10.6690690;4.4843856;-0.1217613;8.0000000;0.0000000 -311.1364607;23.2224562;10.4748685;4.4597456;-0.1247108;8.0000000;0.0000000 -311.3364199;23.1700437;10.2818994;4.4345059;-0.1277469;8.0000000;0.0000000 -311.5363790;23.1127218;10.0903405;4.4086509;-0.1308717;8.0000000;0.0000000 -311.7363382;23.0504077;9.9003482;4.3821777;-0.1337365;8.0000000;0.0000000 -311.9362974;22.9830350;9.7120853;4.3551879;-0.1362306;8.0000000;0.0000000 -312.1362565;22.9105612;9.5257326;4.3276905;-0.1388187;8.0000000;0.0000000 -312.3362157;22.8329652;9.3414543;4.3000578;-0.1372378;8.0000000;0.0000000 -312.5361748;22.7503397;9.1593699;4.2728034;-0.1353783;8.0000000;0.0000000 -312.7361340;22.6628168;8.9795894;4.2459345;-0.1330462;8.0000000;0.0000000 -312.9360932;22.5705449;8.8022019;4.2196368;-0.1300009;8.0000000;0.0000000 -313.1360523;22.4736897;8.6272663;4.1939383;-0.1270473;8.0000000;0.0000000 -313.3360115;22.3724265;8.4548556;4.1688215;-0.1241889;8.0000000;0.0000000 -313.5359707;22.2669099;8.2850071;4.1442687;-0.1214000;8.0000000;0.0000000 -313.7359298;22.1573019;8.1177706;4.1202652;-0.1187035;8.0000000;0.0000000 -313.9358890;22.0437573;7.9531853;4.0967926;-0.1160838;8.0000000;0.0000000 -314.1358482;21.9264177;7.7912724;4.0738364;-0.1135291;8.0000000;0.0000000 -314.3358073;21.8054402;7.6320748;4.0513836;-0.1110612;8.0000000;0.0000000 -314.5357665;21.6809520;7.4755963;4.0294182;-0.1086445;8.0000000;0.0000000 -314.7357257;21.5530946;7.3218599;4.0079300;-0.1062963;8.0000000;0.0000000 -314.9356848;21.4220012;7.1708789;3.9869051;-0.1040065;8.0000000;0.0000000 -315.1356440;21.2877885;7.0226482;3.9663323;-0.1017636;8.0000000;0.0000000 -315.3356032;21.1505978;6.8771903;3.9462039;-0.0995754;8.0000000;0.0000000 -315.5355623;21.0105312;6.7344855;3.9265084;-0.0974245;8.0000000;0.0000000 -315.7355215;20.8677120;6.5945371;3.9072387;-0.0953197;8.0000000;0.0000000 -315.9354807;20.7222548;6.4573394;3.8883863;-0.0932518;8.0000000;0.0000000 -316.1354398;20.5742557;6.3228696;3.8699429;-0.0912183;8.0000000;0.0000000 -316.3353990;20.4238404;6.1911320;3.8519039;-0.0892196;8.0000000;0.0000000 -316.5353581;20.2710912;6.0620922;3.8342610;-0.0872480;8.0000000;0.0000000 -316.7353173;20.1161147;5.9357375;3.8170095;-0.0853051;8.0000000;0.0000000 -316.9352765;19.9590092;5.8120474;3.8001448;-0.0833827;8.0000000;0.0000000 -317.1352356;19.7998544;5.6909872;3.7836611;-0.0814857;8.0000000;0.0000000 -317.3351948;19.6387595;5.5725445;3.7675561;-0.0796051;8.0000000;0.0000000 -317.5351540;19.4757927;5.4566760;3.7518246;-0.0777437;8.0000000;0.0000000 -317.7351131;19.3110449;5.3433553;3.7364633;-0.0759023;8.0000000;0.0000000 -317.9350723;19.1445993;5.2325501;3.7214691;-0.0740742;8.0000000;0.0000000 -318.1350315;18.9765236;5.1242177;3.7068382;-0.0722644;8.0000000;0.0000000 -318.3349906;18.8069091;5.0183308;3.6925691;-0.0704604;8.0000000;0.0000000 -318.5349498;18.6358141;4.9148409;3.6786591;-0.0686695;8.0000000;0.0000000 -318.7349090;18.4633145;4.8137102;3.6651057;-0.0668922;8.0000000;0.0000000 -318.9348681;18.2894801;4.7148971;3.6519071;-0.0651237;8.0000000;0.0000000 -319.1348273;18.1143687;4.6183533;3.6390605;-0.0633680;8.0000000;0.0000000 -319.3347865;17.9380538;4.5240392;3.6265647;-0.0616190;8.0000000;0.0000000 -319.5347456;17.7605870;4.4319029;3.6144174;-0.0598791;8.0000000;0.0000000 -319.7347048;17.5820297;4.3418981;3.6026172;-0.0581476;8.0000000;0.0000000 -319.9346640;17.4024394;4.2539762;3.5911628;-0.0564208;8.0000000;0.0000000 -320.1346231;17.2218663;4.1680848;3.5800528;-0.0547025;8.0000000;0.0000000 -320.3345823;17.0403667;4.0841747;3.5692860;-0.0529886;8.0000000;0.0000000 -320.5345414;16.8579872;4.0021919;3.5588613;-0.0512804;8.0000000;0.0000000 -320.7345006;16.6747764;3.9220834;3.5487775;-0.0495782;8.0000000;0.0000000 -320.9344598;16.4907808;3.8437953;3.5390338;-0.0478794;8.0000000;0.0000000 -321.1344189;16.3060443;3.7672724;3.5296294;-0.0461857;8.0000000;0.0000000 -321.3343781;16.1206078;3.6924584;3.5205634;-0.0444916;8.0000000;0.0000000 -321.5343373;15.9345142;3.6192975;3.5118361;-0.0428005;8.0000000;0.0000000 -321.7342964;15.7478008;3.5477317;3.5034465;-0.0411129;8.0000000;0.0000000 -321.9342556;15.5605048;3.4777031;3.4953941;-0.0394267;8.0000000;0.0000000 -322.1342148;15.3726650;3.4091542;3.4876788;-0.0377435;8.0000000;0.0000000 -322.3341739;15.1843091;3.3420233;3.4802999;-0.0360604;8.0000000;0.0000000 -322.5341331;14.9954770;3.2762534;3.4732574;-0.0343788;8.0000000;0.0000000 -322.7340923;14.8061965;3.2117829;3.4665511;-0.0326984;8.0000000;0.0000000 -322.9340514;14.6164972;3.1485510;3.4601807;-0.0310180;8.0000000;0.0000000 -323.1340106;14.4264138;3.0864982;3.4541464;-0.0293389;8.0000000;0.0000000 -323.3339698;14.2359629;3.0255595;3.4484476;-0.0276594;8.0000000;0.0000000 -323.5339289;14.0451824;2.9656765;3.4430848;-0.0259804;8.0000000;0.0000000 -323.7338881;13.8540925;2.9067851;3.4380576;-0.0243015;8.0000000;0.0000000 -323.9338473;13.6627167;2.8488224;3.4333661;-0.0226220;8.0000000;0.0000000 -324.1338064;13.4710868;2.7917278;3.4290106;-0.0209429;8.0000000;0.0000000 -324.3337656;13.2792106;2.7354335;3.4249909;-0.0192613;8.0000000;0.0000000 -324.5337247;13.0871248;2.6798804;3.4213076;-0.0175795;8.0000000;0.0000000 -324.7336839;12.8948440;2.6250025;3.4179608;-0.0158927;8.0000000;0.0000000 -324.9336431;12.7023872;2.5707352;3.4149522;-0.0141992;8.0000000;0.0000000 -325.1336022;12.5097844;2.5170167;3.4122823;-0.0125057;8.0000000;0.0000000 -325.3335614;12.3170374;2.4637769;3.4099526;-0.0107948;8.0000000;0.0000000 -325.5335206;12.1241829;2.4109552;3.4079653;-0.0090826;8.0000000;0.0000000 -325.7334797;11.9312315;2.3584834;3.4063204;-0.0073680;8.0000000;0.0000000 -325.9334389;11.7382001;2.3062953;3.4050188;-0.0056504;8.0000000;0.0000000 -326.1333981;11.5451184;2.2543275;3.4040608;-0.0039323;8.0000000;0.0000000 -326.3333572;11.3519847;2.2025108;3.4034126;-0.0025673;8.0000000;0.0000000 -326.5333164;11.1588308;2.1507949;3.4030340;-0.0012197;8.0000000;0.0000000 -326.7332756;10.9656646;2.0991270;3.4029026;-0.0003623;8.0000000;0.0000000 -326.9332347;10.7724917;2.0474734;3.4028569;-0.0000952;8.0000000;0.0000000 -327.1331939;10.5793200;1.9958241;3.4028645;0.0001718;8.0000000;0.0000000 -327.3331531;10.3861479;1.9441693;3.4029001;0.0001725;8.0000000;0.0000000 -327.5331122;10.1929777;1.8925078;3.4029335;0.0001608;8.0000000;0.0000000 -327.7330714;9.9998090;1.8408401;3.4029645;0.0001497;8.0000000;0.0000000 -327.9330306;9.8066419;1.7891666;3.4029934;0.0001393;8.0000000;0.0000000 -328.1329897;9.6134764;1.7374878;3.4030202;0.0001288;8.0000000;0.0000000 -328.3329489;9.4203120;1.6858039;3.4030452;0.0001213;8.0000000;0.0000000 -328.5329080;9.2271490;1.6341154;3.4030687;0.0001139;8.0000000;0.0000000 -328.7328672;9.0339871;1.5824224;3.4030907;0.0001072;8.0000000;0.0000000 -328.9328264;8.8408263;1.5307254;3.4031116;0.0001011;8.0000000;0.0000000 -329.1327855;8.6476667;1.4790244;3.4031312;0.0000951;8.0000000;0.0000000 -329.3327447;8.4545079;1.4273197;3.4031496;0.0000895;8.0000000;0.0000000 -329.5327039;8.2613501;1.3756116;3.4031670;0.0000839;8.0000000;0.0000000 -329.7326630;8.0681932;1.3239002;3.4031832;0.0000785;8.0000000;0.0000000 -329.9326222;7.8750370;1.2721859;3.4031984;0.0000734;8.0000000;0.0000000 -330.1325814;7.6818817;1.2204686;3.4032125;0.0000682;8.0000000;0.0000000 -330.3325405;7.4887270;1.1687488;3.4032257;0.0000635;8.0000000;0.0000000 -330.5324997;7.2955730;1.1170265;3.4032379;0.0000588;8.0000000;0.0000000 -330.7324589;7.1024196;1.0653019;3.4032492;0.0000543;8.0000000;0.0000000 -330.9324180;6.9092667;1.0135752;3.4032596;0.0000500;8.0000000;0.0000000 -331.1323772;6.7161145;0.9618466;3.4032692;0.0000457;8.0000000;0.0000000 -331.3323364;6.5229626;0.9101162;3.4032780;0.0000419;8.0000000;0.0000000 -331.5322955;6.3298112;0.8583842;3.4032859;0.0000381;8.0000000;0.0000000 -331.7322547;6.1366602;0.8066508;3.4032932;0.0000345;8.0000000;0.0000000 -331.9322138;5.9435095;0.7549160;3.4032997;0.0000311;8.0000000;0.0000000 -332.1321730;5.7503592;0.7031800;3.4033056;0.0000278;8.0000000;0.0000000 -332.3321322;5.5572091;0.6514429;3.4033109;0.0000249;8.0000000;0.0000000 -332.5320913;5.3640593;0.5997049;3.4033156;0.0000220;8.0000000;0.0000000 -332.7320505;5.1709097;0.5479660;3.4033197;0.0000194;8.0000000;0.0000000 -332.9320097;4.9777604;0.4962264;3.4033234;0.0000171;8.0000000;0.0000000 -333.1319688;4.7846112;0.4444861;3.4033265;0.0000147;8.0000000;0.0000000 -333.3319280;4.5914621;0.3927452;3.4033293;0.0000129;8.0000000;0.0000000 -333.5318872;4.3983133;0.3410038;3.4033317;0.0000112;8.0000000;0.0000000 -333.7318463;4.2051645;0.2892620;3.4033338;0.0000097;8.0000000;0.0000000 -333.9318055;4.0120158;0.2375199;3.4033356;0.0000085;8.0000000;0.0000000 -334.1317647;3.8188672;0.1857774;3.4033372;0.0000073;8.0000000;0.0000000 -334.3317238;3.6257187;0.1340346;3.4033386;0.0000067;8.0000000;0.0000000 -334.5316830;3.4325702;0.0822915;3.4033399;0.0000062;8.0000000;0.0000000 -334.7316422;3.2394218;0.0305483;3.4033411;0.0000060;8.0000000;0.0000000 -334.9316013;3.0462735;-0.0211953;3.4033423;0.0000062;8.0000000;0.0000000 -335.1315605;2.8531252;-0.0729390;3.4033435;0.0000063;8.0000000;0.0000000 -335.3315197;2.6599770;-0.1246830;3.4033449;0.0000072;8.0000000;0.0000000 -335.5314788;2.4668289;-0.1764273;3.4033464;0.0000081;8.0000000;0.0000000 -335.7314380;2.2736809;-0.2281719;3.4033481;0.0000094;8.0000000;0.0000000 -335.9313971;2.0805329;-0.2799168;3.4033502;0.0000111;8.0000000;0.0000000 -336.1313563;1.8873851;-0.3316622;3.4033526;0.0000128;8.0000000;0.0000000 -336.3313155;1.6942374;-0.3834081;3.4033554;0.0000153;8.0000000;0.0000000 -336.5312746;1.5010899;-0.4351546;3.4033587;0.0000179;8.0000000;0.0000000 -336.7312338;1.3079426;-0.4869018;3.4033626;0.0000209;8.0000000;0.0000000 -336.9311930;1.1147954;-0.5386497;3.4033671;0.0000244;8.0000000;0.0000000 -337.1311521;0.9216485;-0.5903987;3.4033723;0.0000278;8.0000000;0.0000000 -337.3311113;0.7285020;-0.6421487;3.4033783;0.0000322;8.0000000;0.0000000 -337.5310705;0.5353557;-0.6938999;3.4033852;0.0000366;8.0000000;0.0000000 -337.7310296;0.3422098;-0.7456526;3.4033930;0.0000416;8.0000000;0.0000000 -337.9309888;0.1490644;-0.7974068;3.4034019;0.0000471;8.0000000;0.0000000 -338.1309480;-0.0440806;-0.8491629;3.4034118;0.0000525;8.0000000;0.0000000