├── CODEOWNERS ├── .DS_Store ├── misc ├── map.png ├── .DS_Store ├── enroute.png ├── high_up.png └── in_the_trees.png ├── setup.cfg ├── writeup_template.md ├── README.md ├── planning_utils.py ├── backyard_flyer_solution.py ├── motion_planning.py └── colliders.csv /CODEOWNERS: -------------------------------------------------------------------------------- 1 | * @udacity/fcnd 2 | -------------------------------------------------------------------------------- /.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mimoralea/FCND-Motion-Planning/master/.DS_Store -------------------------------------------------------------------------------- /misc/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mimoralea/FCND-Motion-Planning/master/misc/map.png -------------------------------------------------------------------------------- /misc/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mimoralea/FCND-Motion-Planning/master/misc/.DS_Store -------------------------------------------------------------------------------- /misc/enroute.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mimoralea/FCND-Motion-Planning/master/misc/enroute.png -------------------------------------------------------------------------------- /misc/high_up.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mimoralea/FCND-Motion-Planning/master/misc/high_up.png -------------------------------------------------------------------------------- /misc/in_the_trees.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mimoralea/FCND-Motion-Planning/master/misc/in_the_trees.png -------------------------------------------------------------------------------- /setup.cfg: -------------------------------------------------------------------------------- 1 | [flake8] 2 | max-line-length = 120 3 | # W293: blank line contains whitespace 4 | # W291: trailing whitespace 5 | ignore = W293,W291 6 | 7 | [isort] 8 | line_length = 120 9 | not_skip = __init__.py 10 | 11 | [yapf] 12 | based_on_style = google 13 | column_limit = 120 14 | -------------------------------------------------------------------------------- /writeup_template.md: -------------------------------------------------------------------------------- 1 | ## Project: 3D Motion Planning 2 | ![Quad Image](./misc/enroute.png) 3 | 4 | --- 5 | 6 | 7 | # Required Steps for a Passing Submission: 8 | 1. Load the 2.5D map in the colliders.csv file describing the environment. 9 | 2. Discretize the environment into a grid or graph representation. 10 | 3. Define the start and goal locations. 11 | 4. Perform a search using A* or other search algorithm. 12 | 5. Use a collinearity test or ray tracing method (like Bresenham) to remove unnecessary waypoints. 13 | 6. Return waypoints in local ECEF coordinates (format for `self.all_waypoints` is [N, E, altitude, heading], where the drone’s start location corresponds to [0, 0, 0, 0]. 14 | 7. Write it up. 15 | 8. Congratulations! Your Done! 16 | 17 | ## [Rubric](https://review.udacity.com/#!/rubrics/1534/view) Points 18 | ### Here I will consider the rubric points individually and describe how I addressed each point in my implementation. 19 | 20 | --- 21 | ### Writeup / README 22 | 23 | #### 1. Provide a Writeup / README that includes all the rubric points and how you addressed each one. You can submit your writeup as markdown or pdf. 24 | 25 | You're reading it! Below I describe how I addressed each rubric point and where in my code each point is handled. 26 | 27 | ### Explain the Starter Code 28 | 29 | #### 1. Explain the functionality of what's provided in `motion_planning.py` and `planning_utils.py` 30 | These scripts contain a basic planning implementation that includes... 31 | 32 | And here's a lovely image of my results (ok this image has nothing to do with it, but it's a nice example of how to include images in your writeup!) 33 | ![Top Down View](./misc/high_up.png) 34 | 35 | Here's | A | Snappy | Table 36 | --- | --- | --- | --- 37 | 1 | `highlight` | **bold** | 7.41 38 | 2 | a | b | c 39 | 3 | *italic* | text | 403 40 | 4 | 2 | 3 | abcd 41 | 42 | ### Implementing Your Path Planning Algorithm 43 | 44 | #### 1. Set your global home position 45 | Here students should read the first line of the csv file, extract lat0 and lon0 as floating point values and use the self.set_home_position() method to set global home. Explain briefly how you accomplished this in your code. 46 | 47 | 48 | And here is a lovely picture of our downtown San Francisco environment from above! 49 | ![Map of SF](./misc/map.png) 50 | 51 | #### 2. Set your current local position 52 | Here as long as you successfully determine your local position relative to global home you'll be all set. Explain briefly how you accomplished this in your code. 53 | 54 | 55 | Meanwhile, here's a picture of me flying through the trees! 56 | ![Forest Flying](./misc/in_the_trees.png) 57 | 58 | #### 3. Set grid start position from local position 59 | This is another step in adding flexibility to the start location. As long as it works you're good to go! 60 | 61 | #### 4. Set grid goal position from geodetic coords 62 | This step is to add flexibility to the desired goal location. Should be able to choose any (lat, lon) within the map and have it rendered to a goal location on the grid. 63 | 64 | #### 5. Modify A* to include diagonal motion (or replace A* altogether) 65 | Minimal requirement here is to modify the code in planning_utils() to update the A* implementation to include diagonal motions on the grid that have a cost of sqrt(2), but more creative solutions are welcome. Explain the code you used to accomplish this step. 66 | 67 | #### 6. Cull waypoints 68 | For this step you can use a collinearity test or ray tracing method like Bresenham. The idea is simply to prune your path of unnecessary waypoints. Explain the code you used to accomplish this step. 69 | 70 | 71 | 72 | ### Execute the flight 73 | #### 1. Does it work? 74 | It works! 75 | 76 | ### Double check that you've met specifications for each of the [rubric](https://review.udacity.com/#!/rubrics/1534/view) points. 77 | 78 | # Extra Challenges: Real World Planning 79 | 80 | For an extra challenge, consider implementing some of the techniques described in the "Real World Planning" lesson. You could try implementing a vehicle model to take dynamic constraints into account, or implement a replanning method to invoke if you get off course or encounter unexpected obstacles. 81 | 82 | 83 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # FCND - 3D Motion Planning 2 | ![Quad Image](./misc/enroute.png) 3 | 4 | 5 | 6 | This project is a continuation of the Backyard Flyer project where you executed a simple square shaped flight path. In this project you will integrate the techniques that you have learned throughout the last several lessons to plan a path through an urban environment. Check out the [project rubric](https://review.udacity.com/#!/rubrics/1534/view) for more detail on what constitutes a passing submission. 7 | 8 | ## Option to do this project in a GPU backed virtual machine in the Udacity classroom! 9 | Rather than downloading the simulator and starter files you can simply complete this project in a virual workspace in the Udacity classroom! Follow [these instructions](https://classroom.udacity.com/nanodegrees/nd787/parts/5aa0a956-4418-4a41-846f-cb7ea63349b3/modules/0c12632a-b59a-41c1-9694-2b3508f47ce7/lessons/5f628104-5857-4a3f-93f0-d8a53fe6a8fd/concepts/ab09b378-f85f-49f4-8845-d59025dd8a8e?contentVersion=1.0.0&contentLocale=en-us) to proceed with the VM. 10 | 11 | ## To complete this project on your local machine, follow these instructions: 12 | ### Step 1: Download the Simulator 13 | This is a new simulator environment! 14 | 15 | Download the Motion-Planning simulator for this project that's appropriate for your operating system from the [simulator releases respository](https://github.com/udacity/FCND-Simulator-Releases/releases). 16 | 17 | ### Step 2: Set up your Python Environment 18 | If you haven't already, set up your Python environment and get all the relevant packages installed using Anaconda following instructions in [this repository](https://github.com/udacity/FCND-Term1-Starter-Kit) 19 | 20 | ### Step 3: Clone this Repository 21 | ```sh 22 | git clone https://github.com/udacity/FCND-Motion-Planning 23 | ``` 24 | ### Step 4: Test setup 25 | The first task in this project is to test the [solution code](https://github.com/udacity/FCND-Motion-Planning/blob/master/backyard_flyer_solution.py) for the Backyard Flyer project in this new simulator. Verify that your Backyard Flyer solution code works as expected and your drone can perform the square flight path in the new simulator. To do this, start the simulator and run the [`backyard_flyer_solution.py`](https://github.com/udacity/FCND-Motion-Planning/blob/master/backyard_flyer_solution.py) script. 26 | 27 | ```sh 28 | source activate fcnd # if you haven't already sourced your Python environment, do so now. 29 | python backyard_flyer_solution.py 30 | ``` 31 | The quad should take off, fly a square pattern and land, just as in the previous project. If everything functions as expected then you are ready to start work on this project. 32 | 33 | ### Step 5: Inspect the relevant files 34 | For this project, you are provided with two scripts, `motion_planning.py` and `planning_utils.py`. Here you'll also find a file called `colliders.csv`, which contains the 2.5D map of the simulator environment. 35 | 36 | ### Step 6: Explain what's going on in `motion_planning.py` and `planning_utils.py` 37 | 38 | `motion_planning.py` is basically a modified version of `backyard_flyer.py` that leverages some extra functions in `planning_utils.py`. It should work right out of the box. Try running `motion_planning.py` to see what it does. To do this, first start up the simulator, then at the command line: 39 | 40 | ```sh 41 | source activate fcnd # if you haven't already sourced your Python environment, do so now. 42 | python motion_planning.py 43 | ``` 44 | 45 | You should see the quad fly a jerky path of waypoints to the northeast for about 10 m then land. What's going on here? Your first task in this project is to explain what's different about `motion_planning.py` from the `backyard_flyer_solution.py` script, and how the functions provided in `planning_utils.py` work. 46 | 47 | ### Step 7: Write your planner 48 | 49 | Your planning algorithm is going to look something like the following: 50 | 51 | - Load the 2.5D map in the `colliders.csv` file describing the environment. 52 | - Discretize the environment into a grid or graph representation. 53 | - Define the start and goal locations. You can determine your home location from `self._latitude` and `self._longitude`. 54 | - Perform a search using A* or other search algorithm. 55 | - Use a collinearity test or ray tracing method (like Bresenham) to remove unnecessary waypoints. 56 | - Return waypoints in local ECEF coordinates (format for `self.all_waypoints` is [N, E, altitude, heading], where the drone’s start location corresponds to [0, 0, 0, 0]). 57 | 58 | Some of these steps are already implemented for you and some you need to modify or implement yourself. See the [rubric](https://review.udacity.com/#!/rubrics/1534/view) for specifics on what you need to modify or implement. 59 | 60 | ### Step 8: Write it up! 61 | When you're finished, complete a detailed writeup of your solution and discuss how you addressed each step. You can use the [`writeup_template.md`](./writeup_template.md) provided here or choose a different format, just be sure to describe clearly the steps you took and code you used to address each point in the [rubric](https://review.udacity.com/#!/rubrics/1534/view). And have fun! 62 | 63 | 64 | -------------------------------------------------------------------------------- /planning_utils.py: -------------------------------------------------------------------------------- 1 | from enum import Enum 2 | from queue import PriorityQueue 3 | import numpy as np 4 | 5 | 6 | def create_grid(data, drone_altitude, safety_distance): 7 | """ 8 | Returns a grid representation of a 2D configuration space 9 | based on given obstacle data, drone altitude and safety distance 10 | arguments. 11 | """ 12 | 13 | # minimum and maximum north coordinates 14 | north_min = np.floor(np.min(data[:, 0] - data[:, 3])) 15 | north_max = np.ceil(np.max(data[:, 0] + data[:, 3])) 16 | print(north_min, north_max) 17 | 18 | # minimum and maximum east coordinates 19 | east_min = np.floor(np.min(data[:, 1] - data[:, 4])) 20 | east_max = np.ceil(np.max(data[:, 1] + data[:, 4])) 21 | print(east_min, east_max) 22 | # given the minimum and maximum coordinates we can 23 | # calculate the size of the grid. 24 | north_size = int(np.ceil((north_max - north_min))) 25 | east_size = int(np.ceil((east_max - east_min))) 26 | print(north_size, east_size) 27 | # Initialize an empty grid 28 | grid = np.zeros((north_size, east_size)) 29 | # Center offset for grid 30 | north_min_center = np.min(data[:, 0]) 31 | east_min_center = np.min(data[:, 1]) 32 | # Populate the grid with obstacles 33 | for i in range(data.shape[0]): 34 | north, east, alt, d_north, d_east, d_alt = data[i, :] 35 | 36 | if alt + d_alt + safety_distance > drone_altitude: 37 | obstacle = [ 38 | int(north - d_north - safety_distance - north_min_center), 39 | int(north + d_north + safety_distance - north_min_center), 40 | int(east - d_east - safety_distance - east_min_center), 41 | int(east + d_east + safety_distance - east_min_center), 42 | ] 43 | grid[obstacle[0]:obstacle[1], obstacle[2]:obstacle[3]] = 1 44 | 45 | return grid 46 | 47 | 48 | # Assume all actions cost the same. 49 | class Action(Enum): 50 | """ 51 | An action is represented by a 3 element tuple. 52 | 53 | The first 2 values are the delta of the action relative 54 | to the current grid position. The third and final value 55 | is the cost of performing the action. 56 | """ 57 | 58 | WEST = (0, -1, 1) 59 | EAST = (0, 1, 1) 60 | NORTH = (-1, 0, 1) 61 | SOUTH = (1, 0, 1) 62 | 63 | @property 64 | def cost(self): 65 | return self.value[2] 66 | 67 | @property 68 | def delta(self): 69 | return (self.value[0], self.value[1]) 70 | 71 | 72 | def valid_actions(grid, current_node): 73 | """ 74 | Returns a list of valid actions given a grid and current node. 75 | """ 76 | valid_actions = list(Action) 77 | n, m = grid.shape[0] - 1, grid.shape[1] - 1 78 | x, y = current_node 79 | 80 | # check if the node is off the grid or 81 | # it's an obstacle 82 | 83 | if x - 1 < 0 or grid[x - 1, y] == 1: 84 | valid_actions.remove(Action.NORTH) 85 | if x + 1 > n or grid[x + 1, y] == 1: 86 | valid_actions.remove(Action.SOUTH) 87 | if y - 1 < 0 or grid[x, y - 1] == 1: 88 | valid_actions.remove(Action.WEST) 89 | if y + 1 > m or grid[x, y + 1] == 1: 90 | valid_actions.remove(Action.EAST) 91 | 92 | return valid_actions 93 | 94 | 95 | def a_star(grid, h, start, goal): 96 | """ 97 | Given a grid and heuristic function returns 98 | the lowest cost path from start to goal. 99 | """ 100 | 101 | path = [] 102 | path_cost = 0 103 | queue = PriorityQueue() 104 | queue.put((0, start)) 105 | visited = set(start) 106 | 107 | branch = {} 108 | found = False 109 | 110 | while not queue.empty(): 111 | item = queue.get() 112 | current_cost = item[0] 113 | current_node = item[1] 114 | 115 | if current_node == goal: 116 | print('Found a path.') 117 | found = True 118 | break 119 | else: 120 | # Get the new vertexes connected to the current vertex 121 | for a in valid_actions(grid, current_node): 122 | next_node = (current_node[0] + a.delta[0], current_node[1] + a.delta[1]) 123 | new_cost = current_cost + a.cost + h(next_node, goal) 124 | 125 | if next_node not in visited: 126 | visited.add(next_node) 127 | queue.put((new_cost, next_node)) 128 | 129 | branch[next_node] = (new_cost, current_node, a) 130 | 131 | if found: 132 | # retrace steps 133 | n = goal 134 | path_cost = branch[n][0] 135 | path.append(goal) 136 | while branch[n][1] != start: 137 | path.append(branch[n][1]) 138 | n = branch[n][1] 139 | path.append(branch[n][1]) 140 | else: 141 | print('**********************') 142 | print('Failed to find a path!') 143 | print('**********************') 144 | return path[::-1], path_cost 145 | 146 | def heuristic(position, goal_position): 147 | return np.linalg.norm(np.array(position) - np.array(goal_position)) 148 | 149 | -------------------------------------------------------------------------------- /backyard_flyer_solution.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | """ 3 | Solution to the Backyard Flyer Project. 4 | """ 5 | 6 | import time 7 | from enum import Enum 8 | 9 | import numpy as np 10 | 11 | from udacidrone import Drone 12 | from udacidrone.connection import MavlinkConnection, WebSocketConnection # noqa: F401 13 | from udacidrone.messaging import MsgID 14 | 15 | 16 | class States(Enum): 17 | MANUAL = 0 18 | ARMING = 1 19 | TAKEOFF = 2 20 | WAYPOINT = 3 21 | LANDING = 4 22 | DISARMING = 5 23 | 24 | 25 | class BackyardFlyer(Drone): 26 | 27 | def __init__(self, connection): 28 | super().__init__(connection) 29 | self.target_position = np.array([0.0, 0.0, 0.0]) 30 | self.all_waypoints = [] 31 | self.in_mission = True 32 | self.check_state = {} 33 | 34 | # initial state 35 | self.flight_state = States.MANUAL 36 | 37 | # register all your callbacks here 38 | self.register_callback(MsgID.LOCAL_POSITION, self.local_position_callback) 39 | self.register_callback(MsgID.LOCAL_VELOCITY, self.velocity_callback) 40 | self.register_callback(MsgID.STATE, self.state_callback) 41 | 42 | def local_position_callback(self): 43 | if self.flight_state == States.TAKEOFF: 44 | if -1.0 * self.local_position[2] > 0.95 * self.target_position[2]: 45 | self.all_waypoints = self.calculate_box() 46 | self.waypoint_transition() 47 | elif self.flight_state == States.WAYPOINT: 48 | if np.linalg.norm(self.target_position[0:2] - self.local_position[0:2]) < 1.0: 49 | if len(self.all_waypoints) > 0: 50 | self.waypoint_transition() 51 | else: 52 | if np.linalg.norm(self.local_velocity[0:2]) < 1.0: 53 | self.landing_transition() 54 | 55 | def velocity_callback(self): 56 | if self.flight_state == States.LANDING: 57 | if self.global_position[2] - self.global_home[2] < 0.1: 58 | if abs(self.local_position[2]) < 0.01: 59 | self.disarming_transition() 60 | 61 | def state_callback(self): 62 | if self.in_mission: 63 | if self.flight_state == States.MANUAL: 64 | self.arming_transition() 65 | elif self.flight_state == States.ARMING: 66 | if self.armed: 67 | self.takeoff_transition() 68 | elif self.flight_state == States.DISARMING: 69 | if ~self.armed & ~self.guided: 70 | self.manual_transition() 71 | 72 | def calculate_box(self): 73 | print("Setting Home") 74 | local_waypoints = [[10.0, 0.0, 3.0], [10.0, 10.0, 3.0], [0.0, 10.0, 3.0], [0.0, 0.0, 3.0]] 75 | return local_waypoints 76 | 77 | def arming_transition(self): 78 | print("arming transition") 79 | self.take_control() 80 | self.arm() 81 | self.set_home_position(self.global_position[0], self.global_position[1], 82 | self.global_position[2]) # set the current location to be the home position 83 | 84 | self.flight_state = States.ARMING 85 | 86 | def takeoff_transition(self): 87 | print("takeoff transition") 88 | # self.global_home = np.copy(self.global_position) # can't write to this variable! 89 | target_altitude = 3.0 90 | self.target_position[2] = target_altitude 91 | self.takeoff(target_altitude) 92 | self.flight_state = States.TAKEOFF 93 | 94 | def waypoint_transition(self): 95 | print("waypoint transition") 96 | self.target_position = self.all_waypoints.pop(0) 97 | print('target position', self.target_position) 98 | self.cmd_position(self.target_position[0], self.target_position[1], self.target_position[2], 0.0) 99 | self.flight_state = States.WAYPOINT 100 | 101 | def landing_transition(self): 102 | print("landing transition") 103 | self.land() 104 | self.flight_state = States.LANDING 105 | 106 | def disarming_transition(self): 107 | print("disarm transition") 108 | self.disarm() 109 | self.release_control() 110 | self.flight_state = States.DISARMING 111 | 112 | def manual_transition(self): 113 | print("manual transition") 114 | self.stop() 115 | self.in_mission = False 116 | self.flight_state = States.MANUAL 117 | 118 | def start(self): 119 | self.start_log("Logs", "NavLog.txt") 120 | # self.connect() 121 | 122 | print("starting connection") 123 | # self.connection.start() 124 | 125 | super().start() 126 | 127 | # Only required if they do threaded 128 | # while self.in_mission: 129 | # pass 130 | 131 | self.stop_log() 132 | 133 | 134 | if __name__ == "__main__": 135 | conn = MavlinkConnection('tcp:127.0.0.1:5760', threaded=False, PX4=False) 136 | #conn = WebSocketConnection('ws://127.0.0.1:5760') 137 | drone = BackyardFlyer(conn) 138 | time.sleep(2) 139 | drone.start() 140 | -------------------------------------------------------------------------------- /motion_planning.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | import time 3 | import msgpack 4 | from enum import Enum, auto 5 | 6 | import numpy as np 7 | 8 | from planning_utils import a_star, heuristic, create_grid 9 | from udacidrone import Drone 10 | from udacidrone.connection import MavlinkConnection 11 | from udacidrone.messaging import MsgID 12 | from udacidrone.frame_utils import global_to_local 13 | 14 | 15 | class States(Enum): 16 | MANUAL = auto() 17 | ARMING = auto() 18 | TAKEOFF = auto() 19 | WAYPOINT = auto() 20 | LANDING = auto() 21 | DISARMING = auto() 22 | PLANNING = auto() 23 | 24 | 25 | class MotionPlanning(Drone): 26 | 27 | def __init__(self, connection): 28 | super().__init__(connection) 29 | 30 | self.target_position = np.array([0.0, 0.0, 0.0]) 31 | self.waypoints = [] 32 | self.in_mission = True 33 | self.check_state = {} 34 | 35 | # initial state 36 | self.flight_state = States.MANUAL 37 | 38 | # register all your callbacks here 39 | self.register_callback(MsgID.LOCAL_POSITION, self.local_position_callback) 40 | self.register_callback(MsgID.LOCAL_VELOCITY, self.velocity_callback) 41 | self.register_callback(MsgID.STATE, self.state_callback) 42 | 43 | def local_position_callback(self): 44 | if self.flight_state == States.TAKEOFF: 45 | if -1.0 * self.local_position[2] > 0.95 * self.target_position[2]: 46 | self.waypoint_transition() 47 | elif self.flight_state == States.WAYPOINT: 48 | if np.linalg.norm(self.target_position[0:2] - self.local_position[0:2]) < 1.0: 49 | if len(self.waypoints) > 0: 50 | self.waypoint_transition() 51 | else: 52 | if np.linalg.norm(self.local_velocity[0:2]) < 1.0: 53 | self.landing_transition() 54 | 55 | def velocity_callback(self): 56 | if self.flight_state == States.LANDING: 57 | if self.global_position[2] - self.global_home[2] < 0.1: 58 | if abs(self.local_position[2]) < 0.01: 59 | self.disarming_transition() 60 | 61 | def state_callback(self): 62 | if self.in_mission: 63 | if self.flight_state == States.MANUAL: 64 | self.arming_transition() 65 | elif self.flight_state == States.ARMING: 66 | if self.armed: 67 | self.plan_path() 68 | elif self.flight_state == States.PLANNING: 69 | self.takeoff_transition() 70 | elif self.flight_state == States.DISARMING: 71 | if ~self.armed & ~self.guided: 72 | self.manual_transition() 73 | 74 | def arming_transition(self): 75 | self.flight_state = States.ARMING 76 | print("arming transition") 77 | self.arm() 78 | self.take_control() 79 | 80 | def takeoff_transition(self): 81 | self.flight_state = States.TAKEOFF 82 | print("takeoff transition") 83 | self.takeoff(self.target_position[2]) 84 | 85 | def waypoint_transition(self): 86 | self.flight_state = States.WAYPOINT 87 | print("waypoint transition") 88 | self.target_position = self.waypoints.pop(0) 89 | print('target position', self.target_position) 90 | self.cmd_position(self.target_position[0], self.target_position[1], self.target_position[2], np.deg2rad(0.0)) 91 | 92 | def landing_transition(self): 93 | self.flight_state = States.LANDING 94 | print("landing transition") 95 | self.land() 96 | 97 | def disarming_transition(self): 98 | self.flight_state = States.DISARMING 99 | print("disarm transition") 100 | self.disarm() 101 | self.release_control() 102 | 103 | def manual_transition(self): 104 | self.flight_state = States.MANUAL 105 | print("manual transition") 106 | self.stop() 107 | self.in_mission = False 108 | 109 | def send_waypoints(self): 110 | print("Sending waypoints to simulator ...") 111 | data = msgpack.dumps(self.waypoints) 112 | self.connection._master.write(data) 113 | 114 | def plan_path(self): 115 | self.flight_state = States.PLANNING 116 | print("Searching for a path ...") 117 | TARGET_ALTITUDE = 5 118 | SAFETY_DISTANCE = 3 119 | 120 | self.target_position[2] = TARGET_ALTITUDE 121 | 122 | # TODO: read lat0, lon0 from colliders into floating point values 123 | 124 | # TODO: set home position to (lat0, lon0, 0) 125 | 126 | # TODO: retrieve current global position 127 | 128 | # TODO: convert to current local position using global_to_local() 129 | 130 | print('global home {0}, position {1}, local position {2}'.format(self.global_home, self.global_position, 131 | self.local_position)) 132 | # Read in obstacle map 133 | data = np.loadtxt('colliders.csv', delimiter=',', dtype='Float64', skiprows=3) 134 | # Determine offsets between grid and map 135 | north_offset = int(np.abs(np.min(data[:, 0]))) 136 | east_offset = int(np.abs(np.min(data[:, 1]))) 137 | 138 | print("North offset = {0}, east offset = {1}".format(north_offset, east_offset)) 139 | 140 | # Define a grid for a particular altitude and safety margin around obstacles 141 | grid = create_grid(data, TARGET_ALTITUDE, SAFETY_DISTANCE) 142 | # Define starting point on the grid (this is just grid center) 143 | grid_start = (north_offset, east_offset) 144 | # TODO: convert start position to current position rather than map center 145 | #start = (int(current_local_pos[0]+north_offset), int(current_local_pos[1]+east_offset)) 146 | 147 | # Set goal as some arbitrary position on the grid 148 | grid_goal = (north_offset + 10, east_offset + 10) 149 | # TODO: adapt to set goal as latitude / longitude position and convert 150 | 151 | # Run A* to find a path from start to goal 152 | # TODO: add diagonal motions with a cost of sqrt(2) to your A* implementation 153 | # or move to a different search space such as a graph (not done here) 154 | print('Local Start and Goal: ', grid_start, grid_goal) 155 | path, _ = a_star(grid, heuristic, grid_start, grid_goal) 156 | 157 | # TODO: prune path to minimize number of waypoints 158 | # TODO (if you're feeling ambitious): Try a different approach altogether! 159 | 160 | # Convert path to waypoints 161 | waypoints = [(p[0] - north_offset, p[1] - east_offset, TARGET_ALTITUDE+1) for p in path] 162 | # Set self.waypoints 163 | self.waypoints = waypoints 164 | # TODO: send waypoints to sim 165 | self.send_waypoints() 166 | 167 | def start(self): 168 | self.start_log("Logs", "NavLog.txt") 169 | 170 | print("starting connection") 171 | self.connection.start() 172 | 173 | # Only required if they do threaded 174 | # while self.in_mission: 175 | # pass 176 | 177 | self.stop_log() 178 | 179 | 180 | if __name__ == "__main__": 181 | parser = argparse.ArgumentParser() 182 | parser.add_argument('--port', type=int, default=5760, help='Port number') 183 | parser.add_argument('--host', type=str, default='127.0.0.1', help="host address, i.e. '127.0.0.1'") 184 | args = parser.parse_args() 185 | 186 | conn = MavlinkConnection('tcp:{0}:{1}'.format(args.host, args.port)) 187 | drone = MotionPlanning(conn) 188 | time.sleep(1) 189 | 190 | drone.start() 191 | -------------------------------------------------------------------------------- /colliders.csv: -------------------------------------------------------------------------------- 1 | lat0,lon0 2 | 37.792480,-122.397450 3 | posX,posY,posZ,halfSizeX,halfSizeY,halfSizeZ 4 | -305,-435,85.5,5,5,85.5 5 | -295,-435,85.5,5,5,85.5 6 | -285,-435,85.5,5,5,85.5 7 | -275,-435,85.5,5,5,85.5 8 | -225,-435,50,5,5,50 9 | -215,-435,50,5,5,50 10 | -205,-435,50,5,5,50 11 | -175,-435,1.5,5,5,1.5 12 | -165,-435,46,5,5,46 13 | -155,-435,46,5,5,46 14 | -145,-435,46,5,5,46 15 | -135,-435,46,5,5,46 16 | -125,-435,46,5,5,46 17 | -115,-435,27.5,5,5,27.5 18 | -105,-435,8,5,5,8 19 | -95,-435,8,5,5,8 20 | -85,-435,8,5,5,8 21 | -75.00001,-435,8,5,5,8 22 | -45,-435,20.5,5,5,20.5 23 | -35,-435,20.5,5,5,20.5 24 | -15,-435,7.5,5,5,7.5 25 | -5,-435,12,5,5,12 26 | 5,-435,12,5,5,12 27 | 15,-435,26.5,5,5,26.5 28 | 25.00001,-435,26.5,5,5,26.5 29 | 35,-435,54.5,5,5,54.5 30 | 45.00001,-435,54.5,5,5,54.5 31 | 54.99999,-435,54.5,5,5,54.5 32 | 95,-435,11,5,5,11 33 | 105,-435,11,5,5,11 34 | 115,-435,11,5,5,11 35 | 125,-435,11,5,5,11 36 | 135,-435,11,5,5,11 37 | 355,-435,17,5,5,17 38 | 365,-435,17,5,5,17 39 | 375,-435,17,5,5,17 40 | 385,-435,17,5,5,17 41 | 395,-435,17,5,5,17 42 | 415,-435,5,5,5,5 43 | 425,-435,5,5,5,5 44 | 435,-435,5,5,5,5 45 | 445,-435,5,5,5,5 46 | 485,-435,29.5,5,5,29.5 47 | 495,-435,29.5,5,5,29.5 48 | -305,-425,85.5,5,5,85.5 49 | -295,-425,85.5,5,5,85.5 50 | -285,-425,85.5,5,5,85.5 51 | -275,-425,85.5,5,5,85.5 52 | -225,-425,50,5,5,50 53 | -215,-425,50,5,5,50 54 | -205,-425,50,5,5,50 55 | -175,-425,46,5,5,46 56 | -165,-425,46,5,5,46 57 | -155,-425,46,5,5,46 58 | -145,-425,46,5,5,46 59 | -135,-425,46,5,5,46 60 | -125,-425,46,5,5,46 61 | -115,-425,27.5,5,5,27.5 62 | -105,-425,8,5,5,8 63 | -95,-425,8,5,5,8 64 | -85,-425,8,5,5,8 65 | -75,-425,8,5,5,8 66 | -35,-425,20.5,5,5,20.5 67 | -25,-425,20.5,5,5,20.5 68 | -15,-425,7.5,5,5,7.5 69 | -5,-425,12,5,5,12 70 | 5,-425,12,5,5,12 71 | 15,-425,26.5,5,5,26.5 72 | 25.00001,-425,26.5,5,5,26.5 73 | 35,-425,54.5,5,5,54.5 74 | 44.99999,-425,54.5,5,5,54.5 75 | 55,-425,54.5,5,5,54.5 76 | 305,-425,40.5,5,5,40.5 77 | 315,-425,40.5,5,5,40.5 78 | 355,-425,17,5,5,17 79 | 365,-425,17,5,5,17 80 | 375,-425,17,5,5,17 81 | 385,-425,17,5,5,17 82 | 395,-425,17,5,5,17 83 | 415,-425,5,5,5,5 84 | 425,-425,5,5,5,5 85 | 435,-425,5,5,5,5 86 | 445,-425,5,5,5,5 87 | 485,-425,29.5,5,5,29.5 88 | 495,-425,29.5,5,5,29.5 89 | -305,-415,85.5,5,5,85.5 90 | -295,-415,85.5,5,5,85.5 91 | -285,-415,85.5,5,5,85.5 92 | -275,-415,85.5,5,5,85.5 93 | -235,-415,50,5,5,50 94 | -225,-415,50,5,5,50 95 | -215,-415,50,5,5,50 96 | -205,-415,50,5,5,50 97 | -145,-415,26.5,5,5,26.5 98 | -135,-415,26.5,5,5,26.5 99 | -125,-415,26.5,5,5,26.5 100 | -115,-415,27.5,5,5,27.5 101 | -105,-415,8,5,5,8 102 | -95,-415,8,5,5,8 103 | -85,-415,8,5,5,8 104 | -75,-415,8,5,5,8 105 | -35,-415,20.5,5,5,20.5 106 | -25,-415,20.5,5,5,20.5 107 | -15,-415,7.5,5,5,7.5 108 | -5,-415,7.5,5,5,7.5 109 | 5,-415,12,5,5,12 110 | 15,-415,26.5,5,5,26.5 111 | 205,-415,20.5,5,5,20.5 112 | 265,-415,10.5,5,5,10.5 113 | 295,-415,40.5,5,5,40.5 114 | 305,-415,40.5,5,5,40.5 115 | 315,-415,40.5,5,5,40.5 116 | 355,-415,17,5,5,17 117 | 365,-415,17,5,5,17 118 | 375,-415,17,5,5,17 119 | 385,-415,17,5,5,17 120 | 395,-415,17,5,5,17 121 | 425,-415,4,5,5,4 122 | 435,-415,4,5,5,4 123 | 445,-415,4,5,5,4 124 | 485,-415,29.5,5,5,29.5 125 | 495,-415,29.5,5,5,29.5 126 | -305,-405,85.5,5,5,85.5 127 | -295,-405,85.50001,5,5,85.50001 128 | -285,-405,85.5,5,5,85.5 129 | -275,-405,85.5,5,5,85.5 130 | -215,-405,50,5,5,50 131 | -205,-405,50,5,5,50 132 | -165,-405,26.5,5,5,26.5 133 | -155,-405,26.5,5,5,26.5 134 | -145,-405,26.5,5,5,26.5 135 | -135,-405,26.5,5,5,26.5 136 | -125,-405,26.5,5,5,26.5 137 | -115,-405,27.5,5,5,27.5 138 | -105,-405,27.5,5,5,27.5 139 | -95,-405,8,5,5,8 140 | -85,-405,8,5,5,8 141 | -75,-405,8,5,5,8 142 | 125,-405,49.5,5,5,49.5 143 | 135,-405,49.5,5,5,49.5 144 | 145,-405,49.5,5,5,49.5 145 | 165,-405,20.5,5,5,20.5 146 | 175,-405,20.5,5,5,20.5 147 | 185,-405,20.5,5,5,20.5 148 | 195,-405,20.5,5,5,20.5 149 | 205,-405,20.5,5,5,20.5 150 | 235,-405,10.5,5,5,10.5 151 | 245,-405,10.5,5,5,10.5 152 | 255,-405,10.5,5,5,10.5 153 | 265,-405,10.5,5,5,10.5 154 | 295,-405,40.5,5,5,40.5 155 | 305,-405,40.5,5,5,40.5 156 | 315,-405,40.5,5,5,40.5 157 | 355,-405,17,5,5,17 158 | 365,-405,17,5,5,17 159 | 375,-405,17,5,5,17 160 | 385,-405,17,5,5,17 161 | 395,-405,17,5,5,17 162 | 425,-405,4,5,5,4 163 | 435,-405,4,5,5,4 164 | 445,-405,4,5,5,4 165 | 455,-405,6,5,5,6 166 | -305,-395,7,5,5,7 167 | -295,-395,7,5,5,7 168 | -285,-395,7,5,5,7 169 | -275,-395,7,5,5,7 170 | -265,-395,7,5,5,7 171 | -245,-395,50,5,5,50 172 | -235,-395,50,5,5,50 173 | -225,-395,50,5,5,50 174 | -215,-395,50,5,5,50 175 | -205,-395,50,5,5,50 176 | -165,-395,26.5,5,5,26.5 177 | -155,-395,26.5,5,5,26.5 178 | -145,-395,26.5,5,5,26.5 179 | -135,-395,26.5,5,5,26.5 180 | -125,-395,26.5,5,5,26.5 181 | -115,-395,27.5,5,5,27.5 182 | 55,-395,40.5,5,5,40.5 183 | 65.00001,-395,40.5,5,5,40.5 184 | 105,-395,49.5,5,5,49.5 185 | 115,-395,49.5,5,5,49.5 186 | 125,-395,49.5,5,5,49.5 187 | 135,-395,49.5,5,5,49.5 188 | 145,-395,49.5,5,5,49.5 189 | 165,-395,20.5,5,5,20.5 190 | 175,-395,20.5,5,5,20.5 191 | 185,-395,20.5,5,5,20.5 192 | 195,-395,20.5,5,5,20.5 193 | 205,-395,20.5,5,5,20.5 194 | 235,-395,10.5,5,5,10.5 195 | 245,-395,10.5,5,5,10.5 196 | 255,-395,10.5,5,5,10.5 197 | 265,-395,10.5,5,5,10.5 198 | 275,-395,10.5,5,5,10.5 199 | 295,-395,40.5,5,5,40.5 200 | 305,-395,40.5,5,5,40.5 201 | 315,-395,40.5,5,5,40.5 202 | 325,-395,40.5,5,5,40.5 203 | 365,-395,17,5,5,17 204 | 375,-395,17,5,5,17 205 | 385,-395,17,5,5,17 206 | 395,-395,12.5,5,5,12.5 207 | 425,-395,6,5,5,6 208 | 435,-395,6,5,5,6 209 | 445,-395,6,5,5,6 210 | 455,-395,6,5,5,6 211 | 485,-395,12.5,5,5,12.5 212 | 495,-395,12.5,5,5,12.5 213 | -305,-385,7,5,5,7 214 | -295,-385,7,5,5,7 215 | -285,-385,7,5,5,7 216 | -275,-385,7,5,5,7 217 | -265,-385,7,5,5,7 218 | -245,-385,50,5,5,50 219 | -235,-385,50,5,5,50 220 | -225,-385,50,5,5,50 221 | -215,-385,50,5,5,50 222 | -205,-385,50,5,5,50 223 | 35,-385,40.5,5,5,40.5 224 | 45.00001,-385,40.5,5,5,40.5 225 | 55,-385,40.5,5,5,40.5 226 | 65,-385,40.5,5,5,40.5 227 | 105,-385,49.5,5,5,49.5 228 | 115,-385,49.5,5,5,49.5 229 | 125,-385,49.5,5,5,49.5 230 | 135,-385,49.5,5,5,49.5 231 | 145,-385,49.5,5,5,49.5 232 | 165,-385,20.5,5,5,20.5 233 | 175,-385,20.5,5,5,20.5 234 | 185,-385,20.5,5,5,20.5 235 | 195,-385,20.5,5,5,20.5 236 | 205,-385,20.5,5,5,20.5 237 | 235,-385,10.5,5,5,10.5 238 | 245,-385,10.5,5,5,10.5 239 | 295,-385,40.5,5,5,40.5 240 | 305,-385,40.5,5,5,40.5 241 | 315,-385,40.5,5,5,40.5 242 | 325,-385,40.5,5,5,40.5 243 | 385,-385,12.5,5,5,12.5 244 | 395,-385,12.5,5,5,12.5 245 | 405,-385,12.5,5,5,12.5 246 | 425,-385,6,5,5,6 247 | 455,-385,13,5,5,13 248 | 485,-385,12.5,5,5,12.5 249 | 495,-385,12.5,5,5,12.5 250 | -305,-375,7,5,5,7 251 | -295,-375,7,5,5,7 252 | -285,-375,7,5,5,7 253 | -275,-375,7,5,5,7 254 | -265,-375,7,5,5,7 255 | -255,-375,7,5,5,7 256 | -245,-375,50,5,5,50 257 | -235,-375,50,5,5,50 258 | -225,-375,50,5,5,50 259 | -215,-375,50,5,5,50 260 | -34.99999,-375,34.5,5,5,34.5 261 | -25,-375,34.5,5,5,34.5 262 | 45,-375,40.5,5,5,40.5 263 | 55,-375,40.5,5,5,40.5 264 | 65,-375,40.5,5,5,40.5 265 | 105,-375,49.5,5,5,49.5 266 | 115,-375,49.5,5,5,49.5 267 | 125,-375,49.5,5,5,49.5 268 | 135,-375,49.5,5,5,49.5 269 | 145,-375,49.50001,5,5,49.50001 270 | 165,-375,20.5,5,5,20.5 271 | 175,-375,20.5,5,5,20.5 272 | 235,-375,10.5,5,5,10.5 273 | 245,-375,10.5,5,5,10.5 274 | 295,-375,40.5,5,5,40.5 275 | 305,-375,40.5,5,5,40.5 276 | 315,-375,40.5,5,5,40.5 277 | 325,-375,40.5,5,5,40.5 278 | 375,-375,12.5,5,5,12.5 279 | 385,-375,12.5,5,5,12.5 280 | 395,-375,12.5,5,5,12.5 281 | 405,-375,12.5,5,5,12.5 282 | 425,-375,6.5,5,5,6.5 283 | 435,-375,6.5,5,5,6.5 284 | 445,-375,6.5,5,5,6.5 285 | 455,-375,13,5,5,13 286 | 495,-375,12.5,5,5,12.5 287 | -305,-365,1.5,5,5,1.5 288 | -295,-365,1.5,5,5,1.5 289 | -285,-365,1.5,5,5,1.5 290 | -125,-365,29,5,5,29 291 | -115,-365,29,5,5,29 292 | -105,-365,14,5,5,14 293 | -95,-365,37.5,5,5,37.5 294 | -85,-365,37.5,5,5,37.5 295 | -75,-365,37.5,5,5,37.5 296 | -65.00001,-365,37.5,5,5,37.5 297 | -35,-365,34.5,5,5,34.5 298 | -25.00002,-365,34.5,5,5,34.5 299 | 5,-365,106,5,5,106 300 | 15,-365,106,5,5,106 301 | 25,-365,106,5,5,106 302 | 65.00001,-365,40.5,5,5,40.5 303 | 115,-365,49.5,5,5,49.5 304 | 125,-365,49.5,5,5,49.5 305 | 135,-365,49.5,5,5,49.5 306 | 145,-365,49.5,5,5,49.5 307 | 235,-365,10.5,5,5,10.5 308 | 245,-365,10.5,5,5,10.5 309 | 305,-365,40.5,5,5,40.5 310 | 315,-365,40.5,5,5,40.5 311 | 325,-365,40.5,5,5,40.5 312 | 365,-365,12.5,5,5,12.5 313 | 375,-365,12.5,5,5,12.5 314 | 385,-365,12.5,5,5,12.5 315 | 395,-365,12.5,5,5,12.5 316 | 405,-365,12.5,5,5,12.5 317 | 425,-365,6.5,5,5,6.5 318 | 435,-365,6.5,5,5,6.5 319 | 445,-365,6.5,5,5,6.5 320 | 455,-365,13,5,5,13 321 | 495,-365,12.5,5,5,12.5 322 | -165,-355,29,5,5,29 323 | -155,-355,29,5,5,29 324 | -145,-355,29,5,5,29 325 | -135,-355,29,5,5,29 326 | -125,-355,29,5,5,29 327 | -115,-355,29,5,5,29 328 | -105,-355,14,5,5,14 329 | -95,-355,37.5,5,5,37.5 330 | -85.00001,-355,37.5,5,5,37.5 331 | -75,-355,37.5,5,5,37.5 332 | -65,-355,37.5,5,5,37.5 333 | -25,-355,34.5,5,5,34.5 334 | -15,-355,34.5,5,5,34.5 335 | -5,-355,52.5,5,5,52.5 336 | 5,-355,106,5,5,106 337 | 15,-355,106,5,5,106 338 | 25,-355,52.5,5,5,52.5 339 | 55,-355,40.5,5,5,40.5 340 | 65.00001,-355,40.5,5,5,40.5 341 | 75.00001,-355,40.5,5,5,40.5 342 | 125,-355,49.5,5,5,49.5 343 | 135,-355,49.5,5,5,49.5 344 | 145,-355,49.5,5,5,49.5 345 | 175,-355,61.5,5,5,61.5 346 | 185,-355,61.5,5,5,61.5 347 | 195,-355,61.5,5,5,61.5 348 | 205,-355,61.5,5,5,61.5 349 | 215,-355,61.5,5,5,61.5 350 | 235,-355,10.5,5,5,10.5 351 | 245,-355,10.5,5,5,10.5 352 | 265,-355,10.5,5,5,10.5 353 | 275,-355,10.5,5,5,10.5 354 | 305,-355,40.5,5,5,40.5 355 | 315,-355,40.5,5,5,40.5 356 | 325,-355,40.5,5,5,40.5 357 | 365,-355,12.5,5,5,12.5 358 | 375,-355,12.5,5,5,12.5 359 | 385,-355,12.5,5,5,12.5 360 | 395,-355,12.5,5,5,12.5 361 | 405,-355,12.5,5,5,12.5 362 | 435,-355,6.5,5,5,6.5 363 | 445,-355,6.5,5,5,6.5 364 | 455,-355,13,5,5,13 365 | -155,-345,29,5,5,29 366 | -145,-345,29,5,5,29 367 | -135,-345,29,5,5,29 368 | -125,-345,29,5,5,29 369 | -105,-345,14,5,5,14 370 | -85,-345,37.5,5,5,37.5 371 | -75,-345,37.5,5,5,37.5 372 | -65,-345,37.5,5,5,37.5 373 | -5,-345,52.5,5,5,52.5 374 | 5,-345,52.5,5,5,52.5 375 | 15,-345,106,5,5,106 376 | 24.99999,-345,52.5,5,5,52.5 377 | 44.99999,-345,40.5,5,5,40.5 378 | 55,-345,40.5,5,5,40.5 379 | 135,-345,16.5,5,5,16.5 380 | 145,-345,16.5,5,5,16.5 381 | 155,-345,16.5,5,5,16.5 382 | 175,-345,61.5,5,5,61.5 383 | 185,-345,61.5,5,5,61.5 384 | 195,-345,61.5,5,5,61.5 385 | 205,-345,61.5,5,5,61.5 386 | 215,-345,61.5,5,5,61.5 387 | 245,-345,10.5,5,5,10.5 388 | 255,-345,10.5,5,5,10.5 389 | 265,-345,10.5,5,5,10.5 390 | 275,-345,10.5,5,5,10.5 391 | 315,-345,40.5,5,5,40.5 392 | 325,-345,40.5,5,5,40.5 393 | 365,-345,12.5,5,5,12.5 394 | 375,-345,12.5,5,5,12.5 395 | 385,-345,12.5,5,5,12.5 396 | 395,-345,12.5,5,5,12.5 397 | 405,-345,12.5,5,5,12.5 398 | -155,-335,29,5,5,29 399 | -125,-335,29,5,5,29 400 | -115,-335,29,5,5,29 401 | -105,-335,14,5,5,14 402 | -95,-335,14,5,5,14 403 | -85,-335,37.5,5,5,37.5 404 | -75,-335,37.5,5,5,37.5 405 | -65,-335,37.5,5,5,37.5 406 | 5,-335,52.5,5,5,52.5 407 | 15,-335,106,5,5,106 408 | 25,-335,52.5,5,5,52.5 409 | 35,-335,52.5,5,5,52.5 410 | 115,-335,16.5,5,5,16.5 411 | 125,-335,16.5,5,5,16.5 412 | 135,-335,16.5,5,5,16.5 413 | 145,-335,16.5,5,5,16.5 414 | 155,-335,16.5,5,5,16.5 415 | 175,-335,61.5,5,5,61.5 416 | 185,-335,61.5,5,5,61.5 417 | 195,-335,61.5,5,5,61.5 418 | 205,-335,61.5,5,5,61.5 419 | 215,-335,61.5,5,5,61.5 420 | 245,-335,10.5,5,5,10.5 421 | 255,-335,10.5,5,5,10.5 422 | 265,-335,10.5,5,5,10.5 423 | -275,-325,3,5,5,3 424 | -265,-325,3,5,5,3 425 | -255,-325,3,5,5,3 426 | -225,-325,49.5,5,5,49.5 427 | -215,-325,49.5,5,5,49.5 428 | -205,-325,49.5,5,5,49.5 429 | -155,-325,29,5,5,29 430 | -145,-325,29,5,5,29 431 | -135,-325,29,5,5,29 432 | -125,-325,29,5,5,29 433 | -115,-325,29,5,5,29 434 | -105,-325,47.5,5,5,47.5 435 | -95,-325,47.5,5,5,47.5 436 | -85.00001,-325,47.5,5,5,47.5 437 | -75,-325,47.5,5,5,47.5 438 | -64.99999,-325,47.5,5,5,47.5 439 | -55,-325,47.5,5,5,47.5 440 | -25,-325,20,5,5,20 441 | -15,-325,20,5,5,20 442 | 5,-325,52.5,5,5,52.5 443 | 15,-325,106,5,5,106 444 | 25,-325,106,5,5,106 445 | 35,-325,52.5,5,5,52.5 446 | 65,-325,25.5,5,5,25.5 447 | 115,-325,16.5,5,5,16.5 448 | 125,-325,16.5,5,5,16.5 449 | 135,-325,16.5,5,5,16.5 450 | 145,-325,16.5,5,5,16.5 451 | 155,-325,16.5,5,5,16.5 452 | 175,-325,61.5,5,5,61.5 453 | 185,-325,61.5,5,5,61.5 454 | 195,-325,61.50001,5,5,61.50001 455 | 205,-325,61.5,5,5,61.5 456 | 215,-325,61.5,5,5,61.5 457 | -275,-315,3,5,5,3 458 | -265,-315,3,5,5,3 459 | -255,-315,3,5,5,3 460 | -225,-315,49.5,5,5,49.5 461 | -215,-315,49.5,5,5,49.5 462 | -205,-315,49.5,5,5,49.5 463 | -155,-315,29,5,5,29 464 | -145,-315,29,5,5,29 465 | -135,-315,29,5,5,29 466 | -125,-315,1.5,5,5,1.5 467 | -115,-315,1.5,5,5,1.5 468 | -105,-315,47.5,5,5,47.5 469 | -95,-315,47.5,5,5,47.5 470 | -85.00001,-315,47.5,5,5,47.5 471 | -75,-315,47.5,5,5,47.5 472 | -65,-315,47.5,5,5,47.5 473 | -55,-315,47.5,5,5,47.5 474 | -25,-315,20,5,5,20 475 | -15,-315,20,5,5,20 476 | 5,-315,52.5,5,5,52.5 477 | 15,-315,106,5,5,106 478 | 25,-315,106,5,5,106 479 | 35,-315,52.5,5,5,52.5 480 | 55,-315,25.5,5,5,25.5 481 | 65,-315,25.5,5,5,25.5 482 | 115,-315,16.5,5,5,16.5 483 | 125,-315,16.5,5,5,16.5 484 | 135,-315,16.5,5,5,16.5 485 | 145,-315,16.5,5,5,16.5 486 | 155,-315,16.5,5,5,16.5 487 | 175,-315,61.5,5,5,61.5 488 | 185,-315,61.5,5,5,61.5 489 | 195,-315,61.5,5,5,61.5 490 | 205,-315,61.5,5,5,61.5 491 | 215,-315,61.5,5,5,61.5 492 | -235,-305,49.5,5,5,49.5 493 | -215,-305,49.5,5,5,49.5 494 | -205,-305,49.5,5,5,49.5 495 | -155,-305,1.5,5,5,1.5 496 | -145,-305,1.5,5,5,1.5 497 | -135,-305,1.5,5,5,1.5 498 | -125,-305,24,5,5,24 499 | -115,-305,24,5,5,24 500 | -94.99999,-305,47.5,5,5,47.5 501 | -85,-305,47.5,5,5,47.5 502 | -75,-305,47.5,5,5,47.5 503 | -65,-305,12.5,5,5,12.5 504 | -55,-305,12.5,5,5,12.5 505 | -25,-305,20,5,5,20 506 | -15,-305,20,5,5,20 507 | 5,-305,106,5,5,106 508 | 14.99998,-305,106,5,5,106 509 | 24.99999,-305,106,5,5,106 510 | 65,-305,25.5,5,5,25.5 511 | 75,-305,25.5,5,5,25.5 512 | 125,-305,16.5,5,5,16.5 513 | 135,-305,16.5,5,5,16.5 514 | 145,-305,16.5,5,5,16.5 515 | 155,-305,16.5,5,5,16.5 516 | 175,-305,61.5,5,5,61.5 517 | 185,-305,61.5,5,5,61.5 518 | 415,-305,1.5,5,5,1.5 519 | 425,-305,1.5,5,5,1.5 520 | 435,-305,1.5,5,5,1.5 521 | 445,-305,1.5,5,5,1.5 522 | -235,-295,49.5,5,5,49.5 523 | -225,-295,49.5,5,5,49.5 524 | -215,-295,49.5,5,5,49.5 525 | -205,-295,49.5,5,5,49.5 526 | -195,-295,49.5,5,5,49.5 527 | -155,-295,24,5,5,24 528 | -145,-295,24,5,5,24 529 | -135,-295,24,5,5,24 530 | -125,-295,24,5,5,24 531 | -115,-295,24,5,5,24 532 | -105,-295,24,5,5,24 533 | -95,-295,7,5,5,7 534 | -85,-295,7,5,5,7 535 | -75,-295,8.5,5,5,8.5 536 | -65,-295,12.5,5,5,12.5 537 | -55.00001,-295,12.5,5,5,12.5 538 | -15,-295,20,5,5,20 539 | -5,-295,20,5,5,20 540 | 25,-295,106,5,5,106 541 | 55,-295,25.5,5,5,25.5 542 | 65,-295,25.5,5,5,25.5 543 | 74.99999,-295,25.5,5,5,25.5 544 | 305,-295,14,5,5,14 545 | 315,-295,14,5,5,14 546 | 325,-295,14,5,5,14 547 | 335,-295,14,5,5,14 548 | 415,-295,1.5,5,5,1.5 549 | 425,-295,1.5,5,5,1.5 550 | 435,-295,1.5,5,5,1.5 551 | 445,-295,1.5,5,5,1.5 552 | 455,-295,1.5,5,5,1.5 553 | 465,-295,1.5,5,5,1.5 554 | -235,-285,49.5,5,5,49.5 555 | -225,-285,49.5,5,5,49.5 556 | -215,-285,49.5,5,5,49.5 557 | -205,-285,49.5,5,5,49.5 558 | -195,-285,49.5,5,5,49.5 559 | -155,-285,24,5,5,24 560 | -145,-285,24,5,5,24 561 | -135,-285,24,5,5,24 562 | -125,-285,24,5,5,24 563 | -115,-285,24,5,5,24 564 | -105,-285,24,5,5,24 565 | -95,-285,7,5,5,7 566 | -85,-285,7,5,5,7 567 | -75,-285,8.5,5,5,8.5 568 | -65,-285,12.5,5,5,12.5 569 | -55,-285,12.5,5,5,12.5 570 | -15,-285,20,5,5,20 571 | -5,-285,20,5,5,20 572 | 215,-285,45,5,5,45 573 | 225,-285,45,5,5,45 574 | 275,-285,86.50001,5,5,86.50001 575 | 285,-285,86.5,5,5,86.5 576 | 305,-285,14,5,5,14 577 | 315,-285,14,5,5,14 578 | 325,-285,14,5,5,14 579 | 335,-285,14,5,5,14 580 | 415,-285,1.5,5,5,1.5 581 | 425,-285,1.5,5,5,1.5 582 | 445,-285,1.5,5,5,1.5 583 | 455,-285,1.5,5,5,1.5 584 | 465,-285,1.5,5,5,1.5 585 | -215,-275,49.5,5,5,49.5 586 | -205,-275,49.5,5,5,49.5 587 | -195,-275,49.5,5,5,49.5 588 | -145,-275,24,5,5,24 589 | -135,-275,24,5,5,24 590 | -125,-275,24,5,5,24 591 | -115,-275,24,5,5,24 592 | -105,-275,24,5,5,24 593 | -95,-275,7,5,5,7 594 | -85,-275,7,5,5,7 595 | -75,-275,8.5,5,5,8.5 596 | -65,-275,8.5,5,5,8.5 597 | -55,-275,12.5,5,5,12.5 598 | -45,-275,12.5,5,5,12.5 599 | 145,-275,22.5,5,5,22.5 600 | 155,-275,22.5,5,5,22.5 601 | 185,-275,45,5,5,45 602 | 195,-275,45,5,5,45 603 | 205,-275,45,5,5,45 604 | 215,-275,45,5,5,45 605 | 225,-275,45,5,5,45 606 | 265,-275,86.5,5,5,86.5 607 | 275,-275,86.5,5,5,86.5 608 | 285,-275,86.5,5,5,86.5 609 | 295,-275,86.5,5,5,86.5 610 | 315,-275,14,5,5,14 611 | 325,-275,14,5,5,14 612 | 335,-275,14,5,5,14 613 | 405,-275,1.5,5,5,1.5 614 | 415,-275,1.5,5,5,1.5 615 | 445,-275,1.5,5,5,1.5 616 | 455,-275,1.5,5,5,1.5 617 | 465,-275,1.5,5,5,1.5 618 | -215,-265,49.5,5,5,49.5 619 | -205,-265,49.5,5,5,49.5 620 | -195,-265,49.5,5,5,49.5 621 | -145,-265,24,5,5,24 622 | -135,-265,24,5,5,24 623 | -125,-265,24,5,5,24 624 | -115,-265,24,5,5,24 625 | -105,-265,24,5,5,24 626 | -95,-265,7,5,5,7 627 | -85,-265,7,5,5,7 628 | 125,-265,22.5,5,5,22.5 629 | 135,-265,22.5,5,5,22.5 630 | 145,-265,22.5,5,5,22.5 631 | 155,-265,22.5,5,5,22.5 632 | 185,-265,45,5,5,45 633 | 195,-265,45,5,5,45 634 | 205,-265,45,5,5,45 635 | 215,-265,45,5,5,45 636 | 225,-265,45,5,5,45 637 | 265,-265,86.5,5,5,86.5 638 | 275,-265,86.5,5,5,86.5 639 | 285,-265,86.5,5,5,86.5 640 | 295,-265,86.5,5,5,86.5 641 | 315,-265,14,5,5,14 642 | 325,-265,14,5,5,14 643 | 335,-265,14,5,5,14 644 | 405,-265,1.5,5,5,1.5 645 | 415,-265,1.5,5,5,1.5 646 | 425,-265,1.5,5,5,1.5 647 | -215,-255,49.5,5,5,49.5 648 | -205,-255,49.5,5,5,49.5 649 | -195,-255,49.5,5,5,49.5 650 | 35,-255,12.5,5,5,12.5 651 | 55,-255,30.5,5,5,30.5 652 | 65,-255,30.5,5,5,30.5 653 | 75,-255,30.5,5,5,30.5 654 | 84.99999,-255,30.5,5,5,30.5 655 | 125,-255,22.5,5,5,22.5 656 | 135,-255,22.5,5,5,22.5 657 | 155,-255,22.5,5,5,22.5 658 | 185,-255,45,5,5,45 659 | 195,-255,45,5,5,45 660 | 205,-255,45,5,5,45 661 | 215,-255,45,5,5,45 662 | 225,-255,45,5,5,45 663 | 265,-255,86.5,5,5,86.5 664 | 275,-255,86.5,5,5,86.5 665 | 285,-255,86.5,5,5,86.5 666 | 295,-255,86.5,5,5,86.5 667 | 315,-255,14,5,5,14 668 | 325,-255,14,5,5,14 669 | 335,-255,14,5,5,14 670 | 345,-255,14,5,5,14 671 | -5,-245,14.5,5,5,14.5 672 | 5,-245,14.5,5,5,14.5 673 | 15,-245,14.5,5,5,14.5 674 | 25,-245,12.5,5,5,12.5 675 | 35,-245,12.5,5,5,12.5 676 | 55,-245,30.5,5,5,30.5 677 | 65,-245,30.5,5,5,30.5 678 | 75,-245,30.5,5,5,30.5 679 | 85,-245,30.5,5,5,30.5 680 | 125,-245,16,5,5,16 681 | 135,-245,16,5,5,16 682 | 155,-245,16,5,5,16 683 | 165,-245,16,5,5,16 684 | 175,-245,16,5,5,16 685 | 185,-245,45,5,5,45 686 | 195,-245,45,5,5,45 687 | 205,-245,45,5,5,45 688 | 215,-245,45,5,5,45 689 | 265,-245,86.49999,5,5,86.49999 690 | 275,-245,86.5,5,5,86.5 691 | 285,-245,86.5,5,5,86.5 692 | 295,-245,86.5,5,5,86.5 693 | 315,-245,14,5,5,14 694 | 325,-245,14,5,5,14 695 | 335,-245,14,5,5,14 696 | 345,-245,14,5,5,14 697 | -105,-235,10,5,5,10 698 | -95,-235,10,5,5,10 699 | -84.99999,-235,10,5,5,10 700 | -75,-235,10,5,5,10 701 | -65,-235,42,5,5,42 702 | -55,-235,42,5,5,42 703 | -45,-235,42,5,5,42 704 | -5,-235,14.5,5,5,14.5 705 | 5,-235,14.5,5,5,14.5 706 | 15,-235,14.5,5,5,14.5 707 | 25,-235,12.5,5,5,12.5 708 | 35,-235,12.5,5,5,12.5 709 | 55,-235,30.5,5,5,30.5 710 | 64.99999,-235,30.5,5,5,30.5 711 | 75,-235,30.5,5,5,30.5 712 | 85,-235,30.5,5,5,30.5 713 | 125,-235,16,5,5,16 714 | 135,-235,16,5,5,16 715 | 145,-235,16,5,5,16 716 | 155,-235,16,5,5,16 717 | 165,-235,5.5,5,5,5.5 718 | 175,-235,5.5,5,5,5.5 719 | 195,-235,45,5,5,45 720 | 205,-235,45,5,5,45 721 | 215,-235,45,5,5,45 722 | 265,-235,86.5,5,5,86.5 723 | 275,-235,86.49999,5,5,86.49999 724 | 285,-235,86.5,5,5,86.5 725 | 295,-235,86.49999,5,5,86.49999 726 | 315,-235,14,5,5,14 727 | 325,-235,14,5,5,14 728 | 335,-235,14,5,5,14 729 | 345,-235,14,5,5,14 730 | 355,-235,14,5,5,14 731 | -285,-225,84.5,5,5,84.5 732 | -275,-225,84.50001,5,5,84.50001 733 | -145,-225,27.5,5,5,27.5 734 | -135,-225,27.5,5,5,27.5 735 | -125,-225,27.5,5,5,27.5 736 | -115,-225,27.5,5,5,27.5 737 | -105,-225,10,5,5,10 738 | -94.99999,-225,10,5,5,10 739 | -85,-225,10,5,5,10 740 | -75,-225,10,5,5,10 741 | -65,-225,42,5,5,42 742 | -55,-225,42,5,5,42 743 | -44.99999,-225,42,5,5,42 744 | -4.999985,-225,14.5,5,5,14.5 745 | 5,-225,14.5,5,5,14.5 746 | 15,-225,14.5,5,5,14.5 747 | 25,-225,14.5,5,5,14.5 748 | 35,-225,12.5,5,5,12.5 749 | 55.00001,-225,30.5,5,5,30.5 750 | 64.99999,-225,30.5,5,5,30.5 751 | 74.99999,-225,30.5,5,5,30.5 752 | 85,-225,30.5,5,5,30.5 753 | 135,-225,5.5,5,5,5.5 754 | 145,-225,5.5,5,5,5.5 755 | 155,-225,5.5,5,5,5.5 756 | 165,-225,5.5,5,5,5.5 757 | 175,-225,13,5,5,13 758 | 195,-225,1.5,5,5,1.5 759 | 205,-225,6.5,5,5,6.5 760 | 215,-225,6.5,5,5,6.5 761 | 225,-225,6.5,5,5,6.5 762 | 235,-225,6.5,5,5,6.5 763 | 265,-225,86.5,5,5,86.5 764 | 275,-225,86.5,5,5,86.5 765 | 285,-225,86.5,5,5,86.5 766 | 295,-225,86.5,5,5,86.5 767 | 305,-225,86.5,5,5,86.5 768 | 325,-225,14,5,5,14 769 | 335,-225,14,5,5,14 770 | 345,-225,14,5,5,14 771 | 355,-225,14,5,5,14 772 | -295,-215,84.5,5,5,84.5 773 | -285,-215,84.5,5,5,84.5 774 | -275,-215,84.5,5,5,84.5 775 | -265,-215,84.5,5,5,84.5 776 | -135,-215,27.5,5,5,27.5 777 | -125,-215,27.5,5,5,27.5 778 | -115,-215,27.5,5,5,27.5 779 | -105,-215,10,5,5,10 780 | -94.99999,-215,10,5,5,10 781 | -85.00001,-215,10,5,5,10 782 | -75,-215,10,5,5,10 783 | -65,-215,42,5,5,42 784 | -55.00001,-215,42,5,5,42 785 | -45,-215,42,5,5,42 786 | -5,-215,14.5,5,5,14.5 787 | 5,-215,14.5,5,5,14.5 788 | 15,-215,14.5,5,5,14.5 789 | 25,-215,14.5,5,5,14.5 790 | 35,-215,12.5,5,5,12.5 791 | 45,-215,12.5,5,5,12.5 792 | 55,-215,30.5,5,5,30.5 793 | 65,-215,30.5,5,5,30.5 794 | 135,-215,13,5,5,13 795 | 145,-215,13,5,5,13 796 | 155,-215,13,5,5,13 797 | 165,-215,13,5,5,13 798 | 175,-215,13,5,5,13 799 | 195,-215,1.5,5,5,1.5 800 | 205,-215,5.5,5,5,5.5 801 | 215,-215,5.5,5,5,5.5 802 | 225,-215,5.5,5,5,5.5 803 | 235,-215,5.5,5,5,5.5 804 | 265,-215,86.5,5,5,86.5 805 | 275,-215,86.49999,5,5,86.49999 806 | 285,-215,86.5,5,5,86.5 807 | 295,-215,86.5,5,5,86.5 808 | 305,-215,86.5,5,5,86.5 809 | 325,-215,14,5,5,14 810 | 335,-215,14,5,5,14 811 | 345,-215,14,5,5,14 812 | 355,-215,14,5,5,14 813 | 415,-215,60.5,5,5,60.5 814 | 425,-215,60.5,5,5,60.5 815 | 435,-215,60.5,5,5,60.5 816 | 445,-215,60.5,5,5,60.5 817 | 455,-215,60.5,5,5,60.5 818 | 465,-215,60.5,5,5,60.5 819 | 475,-215,60.5,5,5,60.5 820 | 485,-215,60.5,5,5,60.5 821 | -305,-205,84.5,5,5,84.5 822 | -295,-205,84.5,5,5,84.5 823 | -285,-205,84.5,5,5,84.5 824 | -275,-205,84.5,5,5,84.5 825 | -265,-205,84.5,5,5,84.5 826 | -255,-205,84.5,5,5,84.5 827 | -135,-205,27.5,5,5,27.5 828 | -125,-205,27.5,5,5,27.5 829 | -105,-205,10,5,5,10 830 | -95,-205,10,5,5,10 831 | -85,-205,10,5,5,10 832 | -75.00001,-205,10,5,5,10 833 | -65,-205,42,5,5,42 834 | -55,-205,42,5,5,42 835 | -45,-205,42,5,5,42 836 | -35,-205,42,5,5,42 837 | -5,-205,14.5,5,5,14.5 838 | 5,-205,14.5,5,5,14.5 839 | 15,-205,14.5,5,5,14.5 840 | 25.00001,-205,14.5,5,5,14.5 841 | 135,-205,13,5,5,13 842 | 145,-205,13,5,5,13 843 | 155,-205,13,5,5,13 844 | 165,-205,13,5,5,13 845 | 175,-205,13,5,5,13 846 | 195,-205,1.5,5,5,1.5 847 | 205,-205,1.5,5,5,1.5 848 | 215,-205,1.5,5,5,1.5 849 | 225,-205,8,5,5,8 850 | 235,-205,8,5,5,8 851 | 275,-205,86.5,5,5,86.5 852 | 285,-205,86.5,5,5,86.5 853 | 295,-205,86.5,5,5,86.5 854 | 305,-205,86.5,5,5,86.5 855 | 325,-205,14,5,5,14 856 | 335,-205,14,5,5,14 857 | 345,-205,14,5,5,14 858 | 355,-205,14,5,5,14 859 | 405,-205,60.5,5,5,60.5 860 | 415,-205,60.5,5,5,60.5 861 | 425,-205,60.5,5,5,60.5 862 | 435,-205,60.5,5,5,60.5 863 | 445,-205,60.5,5,5,60.5 864 | 455,-205,60.5,5,5,60.5 865 | 465,-205,60.5,5,5,60.5 866 | 475,-205,60.5,5,5,60.5 867 | 485,-205,60.5,5,5,60.5 868 | -305,-195,84.5,5,5,84.5 869 | -295,-195,84.5,5,5,84.5 870 | -285,-195,84.5,5,5,84.5 871 | -275,-195,84.5,5,5,84.5 872 | -265,-195,84.5,5,5,84.5 873 | -255,-195,84.5,5,5,84.5 874 | -245,-195,84.5,5,5,84.5 875 | -135,-195,1.5,5,5,1.5 876 | -125,-195,1.5,5,5,1.5 877 | -115,-195,1.5,5,5,1.5 878 | -105,-195,1.5,5,5,1.5 879 | -95,-195,10,5,5,10 880 | -85,-195,10,5,5,10 881 | -75.00001,-195,10,5,5,10 882 | -55,-195,42,5,5,42 883 | -45,-195,42,5,5,42 884 | -35,-195,42,5,5,42 885 | 15,-195,72.5,5,5,72.5 886 | 25.00001,-195,72.49999,5,5,72.49999 887 | 35,-195,72.5,5,5,72.5 888 | 75,-195,34.5,5,5,34.5 889 | 85,-195,34.5,5,5,34.5 890 | 95,-195,34.5,5,5,34.5 891 | 135,-195,13,5,5,13 892 | 145,-195,5,5,5,5 893 | 155,-195,5,5,5,5 894 | 165,-195,5,5,5,5 895 | 175,-195,5,5,5,5 896 | 195,-195,1.5,5,5,1.5 897 | 205,-195,1.5,5,5,1.5 898 | 215,-195,1.5,5,5,1.5 899 | 225,-195,8,5,5,8 900 | 235,-195,8,5,5,8 901 | 275,-195,86.5,5,5,86.5 902 | 285,-195,86.5,5,5,86.5 903 | 405,-195,60.5,5,5,60.5 904 | 415,-195,60.5,5,5,60.5 905 | 425,-195,60.5,5,5,60.5 906 | 435,-195,60.5,5,5,60.5 907 | 445,-195,60.5,5,5,60.5 908 | 455,-195,60.5,5,5,60.5 909 | 465,-195,60.5,5,5,60.5 910 | 475,-195,60.5,5,5,60.5 911 | 485,-195,60.5,5,5,60.5 912 | -305,-185,84.5,5,5,84.5 913 | -295,-185,84.5,5,5,84.5 914 | -285,-185,84.5,5,5,84.5 915 | -275,-185,84.49999,5,5,84.49999 916 | -265,-185,84.5,5,5,84.5 917 | -255,-185,84.5,5,5,84.5 918 | -245,-185,84.5,5,5,84.5 919 | -235,-185,84.5,5,5,84.5 920 | -115,-185,1.5,5,5,1.5 921 | -105,-185,1.5,5,5,1.5 922 | -95,-185,10,5,5,10 923 | -85,-185,10,5,5,10 924 | -75,-185,85.5,5,5,85.5 925 | -64.99999,-185,42,5,5,42 926 | -55,-185,42,5,5,42 927 | -45.00001,-185,42,5,5,42 928 | -35.00001,-185,42,5,5,42 929 | -5,-185,72.5,5,5,72.5 930 | 5,-185,72.5,5,5,72.5 931 | 15,-185,72.5,5,5,72.5 932 | 25,-185,72.5,5,5,72.5 933 | 35,-185,72.5,5,5,72.5 934 | 55,-185,34.5,5,5,34.5 935 | 65,-185,34.5,5,5,34.5 936 | 75.00001,-185,34.5,5,5,34.5 937 | 85,-185,34.5,5,5,34.5 938 | 95,-185,34.5,5,5,34.5 939 | 145,-185,5,5,5,5 940 | 155,-185,5,5,5,5 941 | 165,-185,1.5,5,5,1.5 942 | 195,-185,1.5,5,5,1.5 943 | 205,-185,1.5,5,5,1.5 944 | 215,-185,1.5,5,5,1.5 945 | 225,-185,1.5,5,5,1.5 946 | 235,-185,8,5,5,8 947 | 405,-185,60.5,5,5,60.5 948 | 415,-185,60.5,5,5,60.5 949 | 425,-185,60.5,5,5,60.5 950 | 435,-185,60.5,5,5,60.5 951 | 445,-185,60.5,5,5,60.5 952 | 455,-185,60.5,5,5,60.5 953 | 465,-185,60.5,5,5,60.5 954 | 475,-185,60.5,5,5,60.5 955 | 485,-185,60.5,5,5,60.5 956 | -305,-175,84.5,5,5,84.5 957 | -295,-175,84.5,5,5,84.5 958 | -285,-175,84.5,5,5,84.5 959 | -275,-175,84.5,5,5,84.5 960 | -265,-175,84.5,5,5,84.5 961 | -255,-175,84.5,5,5,84.5 962 | -245,-175,84.5,5,5,84.5 963 | -115,-175,85.5,5,5,85.5 964 | -105,-175,85.5,5,5,85.5 965 | -94.99998,-175,85.5,5,5,85.5 966 | -85,-175,85.5,5,5,85.5 967 | -75,-175,85.5,5,5,85.5 968 | -65,-175,42,5,5,42 969 | -55,-175,42,5,5,42 970 | -45,-175,42,5,5,42 971 | -35,-175,42,5,5,42 972 | 5.000015,-175,72.49999,5,5,72.49999 973 | 15,-175,72.5,5,5,72.5 974 | 25,-175,72.5,5,5,72.5 975 | 35,-175,72.5,5,5,72.5 976 | 55,-175,34.5,5,5,34.5 977 | 65,-175,34.5,5,5,34.5 978 | 75,-175,34.5,5,5,34.5 979 | 85,-175,34.5,5,5,34.5 980 | 95,-175,34.5,5,5,34.5 981 | 145,-175,1.5,5,5,1.5 982 | 155,-175,1.5,5,5,1.5 983 | 165,-175,1.5,5,5,1.5 984 | 175,-175,1.5,5,5,1.5 985 | 195,-175,1.5,5,5,1.5 986 | 205,-175,1.5,5,5,1.5 987 | 405,-175,60.5,5,5,60.5 988 | 415,-175,60.5,5,5,60.5 989 | 425,-175,60.5,5,5,60.5 990 | 435,-175,60.5,5,5,60.5 991 | -295,-165,84.5,5,5,84.5 992 | -285,-165,84.5,5,5,84.5 993 | -275,-165,84.50001,5,5,84.50001 994 | -265,-165,84.5,5,5,84.5 995 | -255,-165,84.5,5,5,84.5 996 | -125,-165,85.5,5,5,85.5 997 | -115,-165,85.5,5,5,85.5 998 | -105,-165,85.5,5,5,85.5 999 | -95,-165,85.5,5,5,85.5 1000 | -84.99999,-165,85.5,5,5,85.5 1001 | -75,-165,85.5,5,5,85.5 1002 | -65,-165,85.5,5,5,85.5 1003 | -55,-165,42,5,5,42 1004 | -45,-165,42,5,5,42 1005 | -35,-165,42,5,5,42 1006 | 5,-165,72.5,5,5,72.5 1007 | 15,-165,72.5,5,5,72.5 1008 | 24.99999,-165,72.5,5,5,72.5 1009 | 35,-165,72.5,5,5,72.5 1010 | 55.00001,-165,34.5,5,5,34.5 1011 | 65,-165,34.5,5,5,34.5 1012 | 75,-165,34.5,5,5,34.5 1013 | 85,-165,34.5,5,5,34.5 1014 | 95,-165,34.5,5,5,34.5 1015 | 105,-165,34.5,5,5,34.5 1016 | 345,-165,65,5,5,65 1017 | 355,-165,65,5,5,65 1018 | -285,-155,84.5,5,5,84.5 1019 | -275,-155,84.5,5,5,84.5 1020 | -265,-155,84.5,5,5,84.5 1021 | -215,-155,80,5,5,80 1022 | -205,-155,80.00001,5,5,80.00001 1023 | -125,-155,85.5,5,5,85.5 1024 | -115,-155,85.5,5,5,85.5 1025 | -105,-155,85.5,5,5,85.5 1026 | -95,-155,85.5,5,5,85.5 1027 | -85,-155,85.5,5,5,85.5 1028 | -75,-155,85.5,5,5,85.5 1029 | -65,-155,85.5,5,5,85.5 1030 | -55,-155,42,5,5,42 1031 | -45,-155,42,5,5,42 1032 | -35,-155,42,5,5,42 1033 | 5,-155,72.5,5,5,72.5 1034 | 15,-155,72.5,5,5,72.5 1035 | 25,-155,72.5,5,5,72.5 1036 | 34.99999,-155,72.5,5,5,72.5 1037 | 55,-155,34.5,5,5,34.5 1038 | 65,-155,34.5,5,5,34.5 1039 | 235,-155,1.5,5,5,1.5 1040 | 245,-155,1.5,5,5,1.5 1041 | 285,-155,1.5,5,5,1.5 1042 | 295,-155,1.5,5,5,1.5 1043 | 305,-155,1.5,5,5,1.5 1044 | 335,-155,65,5,5,65 1045 | 345,-155,65,5,5,65 1046 | 355,-155,65,5,5,65 1047 | 365,-155,65,5,5,65 1048 | -305,-145,11.5,5,5,11.5 1049 | -275,-145,84.5,5,5,84.5 1050 | -225,-145,80,5,5,80 1051 | -215,-145,80,5,5,80 1052 | -205,-145,80,5,5,80 1053 | -195,-145,80,5,5,80 1054 | -115,-145,85.5,5,5,85.5 1055 | -105,-145,85.5,5,5,85.5 1056 | -95,-145,85.49999,5,5,85.49999 1057 | -85,-145,85.5,5,5,85.5 1058 | -75,-145,85.5,5,5,85.5 1059 | -65.00001,-145,85.5,5,5,85.5 1060 | -55.00001,-145,42,5,5,42 1061 | -45,-145,42,5,5,42 1062 | -35,-145,42,5,5,42 1063 | -25,-145,42,5,5,42 1064 | 5,-145,72.5,5,5,72.5 1065 | 175,-145,1.5,5,5,1.5 1066 | 185,-145,11.5,5,5,11.5 1067 | 195,-145,11.5,5,5,11.5 1068 | 205,-145,10,5,5,10 1069 | 215,-145,1.5,5,5,1.5 1070 | 225,-145,1.5,5,5,1.5 1071 | 235,-145,1.5,5,5,1.5 1072 | 245,-145,1.5,5,5,1.5 1073 | 285,-145,1.5,5,5,1.5 1074 | 295,-145,1.5,5,5,1.5 1075 | 305,-145,1.5,5,5,1.5 1076 | 315,-145,1.5,5,5,1.5 1077 | 335,-145,65,5,5,65 1078 | 345,-145,65.00001,5,5,65.00001 1079 | 355,-145,65,5,5,65 1080 | 365,-145,65,5,5,65 1081 | -305,-135,11.5,5,5,11.5 1082 | -295,-135,11.5,5,5,11.5 1083 | -235,-135,80,5,5,80 1084 | -225,-135,80,5,5,80 1085 | -215,-135,80,5,5,80 1086 | -205,-135,80,5,5,80 1087 | -195,-135,80,5,5,80 1088 | -105,-135,85.5,5,5,85.5 1089 | -95,-135,85.5,5,5,85.5 1090 | -84.99999,-135,85.5,5,5,85.5 1091 | -75.00001,-135,85.5,5,5,85.5 1092 | -65,-135,85.5,5,5,85.5 1093 | -54.99999,-135,42,5,5,42 1094 | -45,-135,42,5,5,42 1095 | 145,-135,1.5,5,5,1.5 1096 | 155,-135,1.5,5,5,1.5 1097 | 165,-135,1.5,5,5,1.5 1098 | 175,-135,1.5,5,5,1.5 1099 | 185,-135,11.5,5,5,11.5 1100 | 195,-135,11.5,5,5,11.5 1101 | 205,-135,10,5,5,10 1102 | 215,-135,10,5,5,10 1103 | 225,-135,1.5,5,5,1.5 1104 | 235,-135,1.5,5,5,1.5 1105 | 245,-135,1.5,5,5,1.5 1106 | 285,-135,1.5,5,5,1.5 1107 | 295,-135,1.5,5,5,1.5 1108 | 305,-135,1.5,5,5,1.5 1109 | 315,-135,1.5,5,5,1.5 1110 | 335,-135,65,5,5,65 1111 | 345,-135,65,5,5,65 1112 | 355,-135,65,5,5,65 1113 | 365,-135,65,5,5,65 1114 | 475,-135,1.5,5,5,1.5 1115 | 485,-135,1.5,5,5,1.5 1116 | 495,-135,1.5,5,5,1.5 1117 | -305,-125,14,5,5,14 1118 | -295,-125,11.5,5,5,11.5 1119 | -245,-125,80,5,5,80 1120 | -235,-125,80,5,5,80 1121 | -225,-125,80,5,5,80 1122 | -215,-125,80,5,5,80 1123 | -205,-125,80,5,5,80 1124 | 54.99999,-125,6,5,5,6 1125 | 65,-125,6,5,5,6 1126 | 75,-125,6,5,5,6 1127 | 85,-125,6,5,5,6 1128 | 95,-125,6,5,5,6 1129 | 145,-125,1.5,5,5,1.5 1130 | 155,-125,1.5,5,5,1.5 1131 | 165,-125,1.5,5,5,1.5 1132 | 175,-125,1.5,5,5,1.5 1133 | 185,-125,11.5,5,5,11.5 1134 | 195,-125,11.5,5,5,11.5 1135 | 205,-125,10,5,5,10 1136 | 215,-125,10,5,5,10 1137 | 225,-125,1.5,5,5,1.5 1138 | 235,-125,1.5,5,5,1.5 1139 | 245,-125,1.5,5,5,1.5 1140 | 255,-125,1.5,5,5,1.5 1141 | 285,-125,1.5,5,5,1.5 1142 | 295,-125,1.5,5,5,1.5 1143 | 335,-125,65,5,5,65 1144 | 345,-125,65,5,5,65 1145 | 355,-125,65,5,5,65 1146 | 365,-125,65,5,5,65 1147 | 425,-125,1.5,5,5,1.5 1148 | 435,-125,1.5,5,5,1.5 1149 | 475,-125,1.5,5,5,1.5 1150 | 485,-125,1.5,5,5,1.5 1151 | 495,-125,1.5,5,5,1.5 1152 | -305,-115,14,5,5,14 1153 | -255,-115,80,5,5,80 1154 | -245,-115,80,5,5,80 1155 | -235,-115,80,5,5,80 1156 | -225,-115,80,5,5,80 1157 | -215,-115,80,5,5,80 1158 | -175,-115,80,5,5,80 1159 | -165,-115,80,5,5,80 1160 | 15,-115,6,5,5,6 1161 | 25,-115,6,5,5,6 1162 | 35,-115,6,5,5,6 1163 | 45,-115,6,5,5,6 1164 | 55,-115,6,5,5,6 1165 | 65,-115,6,5,5,6 1166 | 75,-115,6,5,5,6 1167 | 85,-115,6,5,5,6 1168 | 95,-115,6,5,5,6 1169 | 155,-115,1.5,5,5,1.5 1170 | 165,-115,34.5,5,5,34.5 1171 | 175,-115,34.5,5,5,34.5 1172 | 185,-115,11.5,5,5,11.5 1173 | 195,-115,11.5,5,5,11.5 1174 | 205,-115,10,5,5,10 1175 | 215,-115,10,5,5,10 1176 | 225,-115,1.5,5,5,1.5 1177 | 235,-115,1.5,5,5,1.5 1178 | 245,-115,1.5,5,5,1.5 1179 | 255,-115,1.5,5,5,1.5 1180 | 335,-115,65,5,5,65 1181 | 345,-115,65,5,5,65 1182 | 355,-115,65,5,5,65 1183 | 365,-115,65,5,5,65 1184 | 425,-115,1.5,5,5,1.5 1185 | 435,-115,1.5,5,5,1.5 1186 | 445,-115,1.5,5,5,1.5 1187 | 455,-115,1.5,5,5,1.5 1188 | 465,-115,1.5,5,5,1.5 1189 | 475,-115,1.5,5,5,1.5 1190 | 485,-115,1.5,5,5,1.5 1191 | 495,-115,1.5,5,5,1.5 1192 | -265,-105,80,5,5,80 1193 | -255,-105,80,5,5,80 1194 | -245,-105,80,5,5,80 1195 | -235,-105,80,5,5,80 1196 | -225,-105,80.00001,5,5,80.00001 1197 | -185,-105,80,5,5,80 1198 | -175,-105,80,5,5,80 1199 | -165,-105,80,5,5,80 1200 | -155,-105,80,5,5,80 1201 | -55,-105,1.5,5,5,1.5 1202 | -45,-105,59,5,5,59 1203 | -35,-105,59,5,5,59 1204 | 15,-105,6,5,5,6 1205 | 25.00001,-105,6,5,5,6 1206 | 35,-105,6,5,5,6 1207 | 45,-105,6,5,5,6 1208 | 55,-105,6,5,5,6 1209 | 65,-105,6,5,5,6 1210 | 75,-105,6,5,5,6 1211 | 85,-105,6,5,5,6 1212 | 155,-105,34.5,5,5,34.5 1213 | 165,-105,34.5,5,5,34.5 1214 | 175,-105,34.5,5,5,34.5 1215 | 185,-105,34.5,5,5,34.5 1216 | 195,-105,34.5,5,5,34.5 1217 | 205,-105,10,5,5,10 1218 | 215,-105,10,5,5,10 1219 | 225,-105,1.5,5,5,1.5 1220 | 235,-105,1.5,5,5,1.5 1221 | 245,-105,1.5,5,5,1.5 1222 | 255,-105,1.5,5,5,1.5 1223 | 335,-105,65,5,5,65 1224 | 345,-105,65,5,5,65 1225 | 355,-105,65,5,5,65 1226 | 365,-105,65.00001,5,5,65.00001 1227 | 375,-105,65,5,5,65 1228 | 425,-105,1.5,5,5,1.5 1229 | 445,-105,1.5,5,5,1.5 1230 | 455,-105,1.5,5,5,1.5 1231 | 465,-105,1.5,5,5,1.5 1232 | 475,-105,1.5,5,5,1.5 1233 | -275,-95,80,5,5,80 1234 | -265,-95,80,5,5,80 1235 | -255,-95,80,5,5,80 1236 | -245,-95,80,5,5,80 1237 | -235,-95,80,5,5,80 1238 | -225,-95,80,5,5,80 1239 | -195,-94.99998,80,5,5,80 1240 | -185,-94.99999,79.99999,5,5,79.99999 1241 | -175,-95.00001,80,5,5,80 1242 | -165,-95.00001,80,5,5,80 1243 | -155,-95.00002,80,5,5,80 1244 | -145,-95.00001,80,5,5,80 1245 | -65.00001,-95,1.5,5,5,1.5 1246 | -55,-95,59,5,5,59 1247 | -45,-95,59,5,5,59 1248 | -35,-95,59,5,5,59 1249 | -25,-95,59,5,5,59 1250 | 15,-94.99999,6,5,5,6 1251 | 24.99999,-95,6,5,5,6 1252 | 35,-95,6,5,5,6 1253 | 45,-94.99999,6,5,5,6 1254 | 55,-95,6,5,5,6 1255 | 65,-95,6,5,5,6 1256 | 75,-95,6,5,5,6 1257 | 155,-95,34.5,5,5,34.5 1258 | 165,-95.00001,34.5,5,5,34.5 1259 | 175,-95,34.5,5,5,34.5 1260 | 185,-95,34.5,5,5,34.5 1261 | 295,-94.99999,1.5,5,5,1.5 1262 | 305,-95,1.5,5,5,1.5 1263 | 345,-95,65,5,5,65 1264 | 355,-95,65,5,5,65 1265 | 365,-95,65.00001,5,5,65.00001 1266 | 375,-95,65,5,5,65 1267 | 455,-94.99999,1.5,5,5,1.5 1268 | 465,-95,1.5,5,5,1.5 1269 | -275,-85,80,5,5,80 1270 | -265,-85,80,5,5,80 1271 | -255,-85,80,5,5,80 1272 | -245,-85,80,5,5,80 1273 | -235,-85,80,5,5,80 1274 | -205,-85,80,5,5,80 1275 | -195,-85,80,5,5,80 1276 | -185,-84.99999,80,5,5,80 1277 | -175,-85,80,5,5,80 1278 | -165,-85.00001,80,5,5,80 1279 | -155,-85,80,5,5,80 1280 | -145,-85,80,5,5,80 1281 | -55,-85.00001,59,5,5,59 1282 | -44.99999,-85.00001,59,5,5,59 1283 | -35,-85,59,5,5,59 1284 | -25,-85,59,5,5,59 1285 | 15,-85,6,5,5,6 1286 | 25,-85,6,5,5,6 1287 | 35,-85,91.5,5,5,91.5 1288 | 45,-85,91.5,5,5,91.5 1289 | 55,-85,91.50001,5,5,91.50001 1290 | 65,-85,91.5,5,5,91.5 1291 | 75,-85,6,5,5,6 1292 | 295,-85,1.5,5,5,1.5 1293 | 305,-85,1.5,5,5,1.5 1294 | 345,-84.99999,65,5,5,65 1295 | 355,-85,65,5,5,65 1296 | 365,-85,65,5,5,65 1297 | 375,-85,65,5,5,65 1298 | -265,-75,80,5,5,80 1299 | -255,-75,79.99999,5,5,79.99999 1300 | -245,-75,80.00001,5,5,80.00001 1301 | -215,-75,80,5,5,80 1302 | -205,-75,80,5,5,80 1303 | -195,-74.99999,80,5,5,80 1304 | -185,-75,80,5,5,80 1305 | -175,-75.00001,80,5,5,80 1306 | -165,-75.00001,80,5,5,80 1307 | -155,-75.00001,80,5,5,80 1308 | -55,-75,59,5,5,59 1309 | -45,-75,59,5,5,59 1310 | -35,-75,59,5,5,59 1311 | -24.99998,-75,59,5,5,59 1312 | -15,-75.00002,59,5,5,59 1313 | 25,-75,91.5,5,5,91.5 1314 | 35,-75,91.5,5,5,91.5 1315 | 45,-75,91.5,5,5,91.5 1316 | 55,-75,91.5,5,5,91.5 1317 | 65,-75,91.5,5,5,91.5 1318 | 75,-75.00001,91.50001,5,5,91.50001 1319 | 195,-75,29.5,5,5,29.5 1320 | 205,-75,29.5,5,5,29.5 1321 | 215,-75,29.5,5,5,29.5 1322 | 225,-75,29.5,5,5,29.5 1323 | 235,-75,29.5,5,5,29.5 1324 | 245,-74.99999,29.5,5,5,29.5 1325 | 295,-75,1.5,5,5,1.5 1326 | 305,-75,1.5,5,5,1.5 1327 | 345,-74.99999,65,5,5,65 1328 | 355,-75,65,5,5,65 1329 | 365,-75,65,5,5,65 1330 | 375,-75,65,5,5,65 1331 | -255,-65,80,5,5,80 1332 | -245,-65,80,5,5,80 1333 | -215,-65,80,5,5,80 1334 | -205,-65,80,5,5,80 1335 | -195,-65,80,5,5,80 1336 | -185,-65,80.00001,5,5,80.00001 1337 | -175,-65,80,5,5,80 1338 | -165,-65,80,5,5,80 1339 | -45,-65,59,5,5,59 1340 | -35.00001,-65,59,5,5,59 1341 | -25,-65,59,5,5,59 1342 | -15,-65,59,5,5,59 1343 | 25,-65,91.5,5,5,91.5 1344 | 35,-65,91.5,5,5,91.5 1345 | 45,-65,91.5,5,5,91.5 1346 | 55,-65,91.5,5,5,91.5 1347 | 65,-65,91.5,5,5,91.5 1348 | 75,-65,91.5,5,5,91.5 1349 | 85,-65,91.5,5,5,91.5 1350 | 175,-65,29.5,5,5,29.5 1351 | 185,-65,29.5,5,5,29.5 1352 | 195,-65.00001,29.5,5,5,29.5 1353 | 205,-65,29.5,5,5,29.5 1354 | 215,-65,29.5,5,5,29.5 1355 | 225,-64.99999,29.5,5,5,29.5 1356 | 235,-65,29.5,5,5,29.5 1357 | 245,-65,29.5,5,5,29.5 1358 | 295,-65,1.5,5,5,1.5 1359 | 305,-65,1.5,5,5,1.5 1360 | 345,-64.99999,65,5,5,65 1361 | 355,-65.00001,65,5,5,65 1362 | 365,-65,65,5,5,65 1363 | -255,-55,6,5,5,6 1364 | -205,-55.00001,80,5,5,80 1365 | -195,-55,80,5,5,80 1366 | -185,-55,79.99999,5,5,79.99999 1367 | -175,-55,80,5,5,80 1368 | -35,-55,59,5,5,59 1369 | -25,-55,59,5,5,59 1370 | -15,-55,59,5,5,59 1371 | 25,-55,91.5,5,5,91.5 1372 | 35,-55,91.5,5,5,91.5 1373 | 45,-55,91.5,5,5,91.5 1374 | 54.99999,-55,91.50001,5,5,91.50001 1375 | 64.99998,-55.00002,91.50001,5,5,91.50001 1376 | 75,-55,91.50001,5,5,91.50001 1377 | 85,-55,91.5,5,5,91.5 1378 | 175,-55,29.5,5,5,29.5 1379 | 185,-55,29.5,5,5,29.5 1380 | 195,-55,29.5,5,5,29.5 1381 | 205,-55,29.5,5,5,29.5 1382 | 215,-54.99999,29.5,5,5,29.5 1383 | 225,-55,29.5,5,5,29.5 1384 | 235,-55,29.5,5,5,29.5 1385 | 245,-55,29.5,5,5,29.5 1386 | 255,-55,29.5,5,5,29.5 1387 | -305,-45,3.5,5,5,3.5 1388 | -265,-45,6,5,5,6 1389 | -255,-45.00001,6,5,5,6 1390 | -245,-45,6,5,5,6 1391 | -195,-45,80,5,5,80 1392 | -185,-45,80.00001,5,5,80.00001 1393 | -125,-45,12.5,5,5,12.5 1394 | -25,-44.99999,59,5,5,59 1395 | -15,-45,59,5,5,59 1396 | 25,-44.99999,91.5,5,5,91.5 1397 | 35,-44.99999,91.5,5,5,91.5 1398 | 45,-45,91.5,5,5,91.5 1399 | 55,-44.99999,91.5,5,5,91.5 1400 | 65,-45,91.5,5,5,91.5 1401 | 74.99999,-45,91.50001,5,5,91.50001 1402 | 85,-45,91.5,5,5,91.5 1403 | 175,-45,29.5,5,5,29.5 1404 | 185,-45,29.5,5,5,29.5 1405 | 195,-45,29.5,5,5,29.5 1406 | 205,-45,29.5,5,5,29.5 1407 | -305,-35,3.5,5,5,3.5 1408 | -295,-35,3.5,5,5,3.5 1409 | -265,-35,6,5,5,6 1410 | -255,-35,6,5,5,6 1411 | -245,-35,6,5,5,6 1412 | -235,-35,6,5,5,6 1413 | -135,-34.99999,12.5,5,5,12.5 1414 | -125,-35,12.5,5,5,12.5 1415 | -115,-35,12.5,5,5,12.5 1416 | -15,-35.00001,59,5,5,59 1417 | 34.99999,-35,91.5,5,5,91.5 1418 | 45,-34.99999,91.5,5,5,91.5 1419 | 55,-35,91.5,5,5,91.5 1420 | 65,-35,91.5,5,5,91.5 1421 | 75,-35,91.5,5,5,91.5 1422 | 345,-35,65,5,5,65 1423 | 355,-35,65,5,5,65 1424 | 365,-35,65,5,5,65 1425 | 375,-35,65,5,5,65 1426 | 385,-35,65,5,5,65 1427 | -305,-25,3.5,5,5,3.5 1428 | -295,-25,3.5,5,5,3.5 1429 | -285,-25,3.5,5,5,3.5 1430 | -255,-25,6,5,5,6 1431 | -245,-25.00001,6,5,5,6 1432 | -235,-25,6,5,5,6 1433 | -225,-25,6,5,5,6 1434 | -145,-25,12.5,5,5,12.5 1435 | -135,-25,12.5,5,5,12.5 1436 | -125,-25,12.5,5,5,12.5 1437 | -115,-25,12.5,5,5,12.5 1438 | -105,-25,12.5,5,5,12.5 1439 | -85,-25,74.5,5,5,74.5 1440 | -75,-25,74.5,5,5,74.5 1441 | 45.00001,-24.99999,91.5,5,5,91.5 1442 | 55,-24.99999,91.5,5,5,91.5 1443 | 65,-25,91.5,5,5,91.5 1444 | 295,-25,1.5,5,5,1.5 1445 | 305,-25,1.5,5,5,1.5 1446 | 315,-25,1.5,5,5,1.5 1447 | 355,-25,65,5,5,65 1448 | 365,-25,65,5,5,65 1449 | 375,-24.99999,65,5,5,65 1450 | 385,-24.99999,65,5,5,65 1451 | -305,-15,16,5,5,16 1452 | -295,-15,3.5,5,5,3.5 1453 | -245,-15.00001,6,5,5,6 1454 | -235,-15,6,5,5,6 1455 | -225,-15,6,5,5,6 1456 | -155,-14.99999,12.5,5,5,12.5 1457 | -145,-15,12.5,5,5,12.5 1458 | -135,-15,12.5,5,5,12.5 1459 | -125,-15,12.5,5,5,12.5 1460 | -115,-15,12.5,5,5,12.5 1461 | -105,-15,12.5,5,5,12.5 1462 | -95,-15,74.5,5,5,74.5 1463 | -85,-15,74.5,5,5,74.5 1464 | -75,-15,74.5,5,5,74.5 1465 | -65,-15,74.5,5,5,74.5 1466 | 205,-15,79.5,5,5,79.5 1467 | 215,-15,79.5,5,5,79.5 1468 | 225,-15,79.50001,5,5,79.50001 1469 | 235,-15,79.50001,5,5,79.50001 1470 | 245,-15,79.5,5,5,79.5 1471 | 255,-15,79.5,5,5,79.5 1472 | 305,-15,1.5,5,5,1.5 1473 | 315,-15,1.5,5,5,1.5 1474 | 355,-15,65,5,5,65 1475 | 365,-14.99999,65,5,5,65 1476 | 375,-15,65,5,5,65 1477 | 385,-14.99999,65,5,5,65 1478 | -305,-4.999998,16,5,5,16 1479 | -275,-5,91.5,5,5,91.5 1480 | -265,-5.000002,91.5,5,5,91.5 1481 | -235,-5,6,5,5,6 1482 | -145,-4.999994,12.5,5,5,12.5 1483 | -135,-4.999996,12.5,5,5,12.5 1484 | -125,-4.999998,12.5,5,5,12.5 1485 | -115,-5.000002,12.5,5,5,12.5 1486 | -105,-5,74.5,5,5,74.5 1487 | -95,-5,74.5,5,5,74.5 1488 | -85.00001,-5,74.49999,5,5,74.49999 1489 | -75,-5.000002,74.5,5,5,74.5 1490 | -65.00001,-5,74.5,5,5,74.5 1491 | -55,-5.000002,74.5,5,5,74.5 1492 | 185,-4.999998,79.5,5,5,79.5 1493 | 195,-4.999998,79.5,5,5,79.5 1494 | 205,-4.999998,79.5,5,5,79.5 1495 | 215,-4.999998,79.5,5,5,79.5 1496 | 225,-4.999998,79.5,5,5,79.5 1497 | 235,-4.999998,79.5,5,5,79.5 1498 | 245,-4.999998,79.5,5,5,79.5 1499 | 255,-5.000002,79.49999,5,5,79.49999 1500 | 305,-4.999998,1.5,5,5,1.5 1501 | 315,-5,1.5,5,5,1.5 1502 | 355,-5.000002,65,5,5,65 1503 | 365,-4.999996,65,5,5,65 1504 | 375,-5.000004,65,5,5,65 1505 | 385,-4.999994,65,5,5,65 1506 | -285,4.999998,91.5,5,5,91.5 1507 | -275,4.999999,91.5,5,5,91.5 1508 | -265,5,91.5,5,5,91.5 1509 | -255,4.999998,91.5,5,5,91.5 1510 | -175,4.999999,74.50001,5,5,74.50001 1511 | -165,4.999998,74.5,5,5,74.5 1512 | -135,5.00001,12.5,5,5,12.5 1513 | -125,5,12.5,5,5,12.5 1514 | -105,5.000002,74.5,5,5,74.5 1515 | -95,5,74.5,5,5,74.5 1516 | -85,5,74.5,5,5,74.5 1517 | -75,4.999998,74.5,5,5,74.5 1518 | -65,4.999999,74.5,5,5,74.5 1519 | -55,5,74.5,5,5,74.5 1520 | -45,5.000002,74.5,5,5,74.5 1521 | 95,5,70,5,5,70 1522 | 105,5,70,5,5,70 1523 | 115,5,70,5,5,70 1524 | 125,5,70,5,5,70 1525 | 195,5,79.5,5,5,79.5 1526 | 205,5,79.5,5,5,79.5 1527 | 215,5.000002,79.5,5,5,79.5 1528 | 225,4.999998,79.5,5,5,79.5 1529 | 235,5,79.5,5,5,79.5 1530 | 245,5,79.5,5,5,79.5 1531 | 255,5.000001,79.5,5,5,79.5 1532 | 305,5,1.5,5,5,1.5 1533 | 315,5,1.5,5,5,1.5 1534 | 355,5,65,5,5,65 1535 | 365,5.000002,65,5,5,65 1536 | 375,4.999994,65,5,5,65 1537 | 385,4.999998,65,5,5,65 1538 | -295,15,91.5,5,5,91.5 1539 | -285,15,91.5,5,5,91.5 1540 | -275,15,91.49999,5,5,91.49999 1541 | -265,15,91.5,5,5,91.5 1542 | -255,15,91.5,5,5,91.5 1543 | -245,15,91.5,5,5,91.5 1544 | -185,15,74.5,5,5,74.5 1545 | -175,15,74.5,5,5,74.5 1546 | -165,14.99999,74.5,5,5,74.5 1547 | -155,15,74.5,5,5,74.5 1548 | -95,15,74.5,5,5,74.5 1549 | -85,15,74.5,5,5,74.5 1550 | -75,15,74.5,5,5,74.5 1551 | -65,15,74.5,5,5,74.5 1552 | -54.99999,15,74.5,5,5,74.5 1553 | -45.00001,15.00001,74.50001,5,5,74.50001 1554 | 85,15,70,5,5,70 1555 | 95,15,70,5,5,70 1556 | 105,15,70,5,5,70 1557 | 115,15,70,5,5,70 1558 | 125,15,70,5,5,70 1559 | 195,15,79.5,5,5,79.5 1560 | 205,15,79.5,5,5,79.5 1561 | 215,15,79.5,5,5,79.5 1562 | 225,15,79.5,5,5,79.5 1563 | 235,15,79.5,5,5,79.5 1564 | 245,15,79.5,5,5,79.5 1565 | 255,15,79.5,5,5,79.5 1566 | 355,15,65,5,5,65 1567 | 365,15,65,5,5,65 1568 | 375,15.00001,65,5,5,65 1569 | 385,15,65,5,5,65 1570 | 395,15,65,5,5,65 1571 | -305,25,91.5,5,5,91.5 1572 | -295,25,91.5,5,5,91.5 1573 | -285,25,91.5,5,5,91.5 1574 | -275,25,91.5,5,5,91.5 1575 | -265,25,91.5,5,5,91.5 1576 | -255,25,91.5,5,5,91.5 1577 | -245,25,91.5,5,5,91.5 1578 | -195,25,74.5,5,5,74.5 1579 | -185,25,74.5,5,5,74.5 1580 | -175,25,74.50001,5,5,74.50001 1581 | -165,25,74.5,5,5,74.5 1582 | -155,25,74.5,5,5,74.5 1583 | -145,25,74.5,5,5,74.5 1584 | -85,25,74.5,5,5,74.5 1585 | -75,25,74.5,5,5,74.5 1586 | -65,25,74.5,5,5,74.5 1587 | -55,25,74.5,5,5,74.5 1588 | 85,25,70,5,5,70 1589 | 95,25,70,5,5,70 1590 | 105,24.99999,70,5,5,70 1591 | 115,25,70,5,5,70 1592 | 125,25,70,5,5,70 1593 | 195,25,79.5,5,5,79.5 1594 | 205,25,79.49999,5,5,79.49999 1595 | 215,25,79.5,5,5,79.5 1596 | 225,25,79.50001,5,5,79.50001 1597 | 235,25,79.5,5,5,79.5 1598 | 245,25,79.5,5,5,79.5 1599 | 355,25.00001,65,5,5,65 1600 | 365,25.00001,65,5,5,65 1601 | 375,25,65,5,5,65 1602 | 385,25,65,5,5,65 1603 | 395,25,65,5,5,65 1604 | -305,35,91.5,5,5,91.5 1605 | -295,35,91.50001,5,5,91.50001 1606 | -285,35,91.5,5,5,91.5 1607 | -275,35,91.49999,5,5,91.49999 1608 | -265,35,91.5,5,5,91.5 1609 | -255,35,91.5,5,5,91.5 1610 | -205,35,74.5,5,5,74.5 1611 | -195,35,74.5,5,5,74.5 1612 | -185,35,74.5,5,5,74.5 1613 | -175,35,74.5,5,5,74.5 1614 | -165,35,74.5,5,5,74.5 1615 | -155,34.99999,74.5,5,5,74.5 1616 | -145,35,74.5,5,5,74.5 1617 | -75,35,74.5,5,5,74.5 1618 | -65,35,74.5,5,5,74.5 1619 | -15,35,41.5,5,5,41.5 1620 | 85,35,70,5,5,70 1621 | 95,35,70,5,5,70 1622 | 105,35,70,5,5,70 1623 | 115,35,70,5,5,70 1624 | 125,35,70,5,5,70 1625 | 135,35,70,5,5,70 1626 | 175,35,1.5,5,5,1.5 1627 | 185,35,1.5,5,5,1.5 1628 | 205,35,79.5,5,5,79.5 1629 | 215,35,79.5,5,5,79.5 1630 | 235,35,1.5,5,5,1.5 1631 | 325,35,1.5,5,5,1.5 1632 | 335,35,1.5,5,5,1.5 1633 | 345,35,1.5,5,5,1.5 1634 | 355,35.00001,65,5,5,65 1635 | 365,35.00002,65,5,5,65 1636 | 375,35,65,5,5,65 1637 | 385,35,65,5,5,65 1638 | 395,35,65,5,5,65 1639 | -295,45,91.5,5,5,91.5 1640 | -285,45,91.5,5,5,91.5 1641 | -275,45,91.5,5,5,91.5 1642 | -265,45,91.5,5,5,91.5 1643 | -205,45,74.5,5,5,74.5 1644 | -195,45,74.5,5,5,74.5 1645 | -185,45,74.5,5,5,74.5 1646 | -175,45,74.5,5,5,74.5 1647 | -165,45,74.5,5,5,74.5 1648 | -155,45,74.5,5,5,74.5 1649 | -25,45,41.5,5,5,41.5 1650 | -15,45.00001,41.5,5,5,41.5 1651 | -5,45,41.5,5,5,41.5 1652 | 85,45,70,5,5,70 1653 | 95,45,70,5,5,70 1654 | 105,45,69.99999,5,5,69.99999 1655 | 115,45,70,5,5,70 1656 | 125,45,70,5,5,70 1657 | 135,45,70,5,5,70 1658 | 175,45,1.5,5,5,1.5 1659 | 185,45,1.5,5,5,1.5 1660 | 195,45,1.5,5,5,1.5 1661 | 205,45,1.5,5,5,1.5 1662 | 215,45,1.5,5,5,1.5 1663 | 235,45,1.5,5,5,1.5 1664 | 245,45,5,5,5,5 1665 | 255,45,5,5,5,5 1666 | 265,45,5,5,5,5 1667 | 275,45,5,5,5,5 1668 | 315,45,1.5,5,5,1.5 1669 | 325,45,1.5,5,5,1.5 1670 | 335,45,1.5,5,5,1.5 1671 | 345,45,1.5,5,5,1.5 1672 | 365,44.99998,65,5,5,65 1673 | 375,45,65,5,5,65 1674 | 385,45,65,5,5,65 1675 | 395,45,65,5,5,65 1676 | -285,55,91.5,5,5,91.5 1677 | -275,55,91.5,5,5,91.5 1678 | -225,55,58.5,5,5,58.5 1679 | -215,55.00001,58.5,5,5,58.5 1680 | -195,55.00001,74.5,5,5,74.5 1681 | -185,55,74.5,5,5,74.5 1682 | -175,55,74.5,5,5,74.5 1683 | -165,55,74.5,5,5,74.5 1684 | -35.00002,55.00001,41.5,5,5,41.5 1685 | -25.00002,55,41.5,5,5,41.5 1686 | -15,55,41.5,5,5,41.5 1687 | -5,55,41.5,5,5,41.5 1688 | 5,55,41.5,5,5,41.5 1689 | 85,55.00001,70,5,5,70 1690 | 95,55,70,5,5,70 1691 | 105,55,70,5,5,70 1692 | 115,55,70,5,5,70 1693 | 175,55,1.5,5,5,1.5 1694 | 185,55,1.5,5,5,1.5 1695 | 195,55,1.5,5,5,1.5 1696 | 205,55,1.5,5,5,1.5 1697 | 215,55,1.5,5,5,1.5 1698 | 235,55,1.5,5,5,1.5 1699 | 245,55,1.5,5,5,1.5 1700 | 255,55,5,5,5,5 1701 | 265,55,4,5,5,4 1702 | 275,55,4,5,5,4 1703 | 315,55,1.5,5,5,1.5 1704 | 325,55,1.5,5,5,1.5 1705 | 335,55,1.5,5,5,1.5 1706 | 345,55.00001,1.5,5,5,1.5 1707 | 385,55,65,5,5,65 1708 | 395,55,65,5,5,65 1709 | -235,65,58.5,5,5,58.5 1710 | -225,65.00001,58.5,5,5,58.5 1711 | -215,65.00001,58.5,5,5,58.5 1712 | -205,65.00001,58.5,5,5,58.5 1713 | -185,65.00001,74.5,5,5,74.5 1714 | -175,65,74.5,5,5,74.5 1715 | -35.00001,65.00001,41.5,5,5,41.5 1716 | -25,65,41.5,5,5,41.5 1717 | -15,65,41.5,5,5,41.5 1718 | -5,65,41.5,5,5,41.5 1719 | 5,65,41.5,5,5,41.5 1720 | 15,65.00001,41.5,5,5,41.5 1721 | 115,65,7.5,5,5,7.5 1722 | 125,65,7.5,5,5,7.5 1723 | 135,65,7.5,5,5,7.5 1724 | 175,65.00001,1.5,5,5,1.5 1725 | 185,65,1.5,5,5,1.5 1726 | 195,65,1.5,5,5,1.5 1727 | 215,65,1.5,5,5,1.5 1728 | 225,65,1.5,5,5,1.5 1729 | 235,65.00001,1.5,5,5,1.5 1730 | 245,65,1.5,5,5,1.5 1731 | 255,65,5.5,5,5,5.5 1732 | 265,65,1.5,5,5,1.5 1733 | 275,65.00001,4,5,5,4 1734 | 315,65,1.5,5,5,1.5 1735 | 325,65,1.5,5,5,1.5 1736 | 335,65,1.5,5,5,1.5 1737 | -245,75,58.5,5,5,58.5 1738 | -235,75,58.5,5,5,58.5 1739 | -225,75.00001,58.5,5,5,58.5 1740 | -215,75,58.5,5,5,58.5 1741 | -205,75,58.5,5,5,58.5 1742 | -195,75,58.5,5,5,58.5 1743 | -165,75.00001,52.5,5,5,52.5 1744 | -155,74.99998,52.5,5,5,52.5 1745 | -55,74.99999,41.5,5,5,41.5 1746 | -45,75.00001,41.5,5,5,41.5 1747 | -35.00001,75,41.5,5,5,41.5 1748 | -25,75,41.5,5,5,41.5 1749 | -15,75,41.5,5,5,41.5 1750 | -5,75.00001,41.5,5,5,41.5 1751 | 15,75,41.5,5,5,41.5 1752 | 25,75,41.5,5,5,41.5 1753 | 115,75,7.5,5,5,7.5 1754 | 125,75,7.5,5,5,7.5 1755 | 135,75,7.5,5,5,7.5 1756 | 185,75,15.5,5,5,15.5 1757 | 205,75,7,5,5,7 1758 | 215,75,1.5,5,5,1.5 1759 | 225,75,1.5,5,5,1.5 1760 | 235,75,1.5,5,5,1.5 1761 | 245,75,1.5,5,5,1.5 1762 | 255,75.00001,5.5,5,5,5.5 1763 | 265,75,1.5,5,5,1.5 1764 | 275,75,4,5,5,4 1765 | 285,75,4,5,5,4 1766 | -255,85,58.5,5,5,58.5 1767 | -245,85,58.5,5,5,58.5 1768 | -235,85,58.5,5,5,58.5 1769 | -225,85,58.5,5,5,58.5 1770 | -215,85,58.5,5,5,58.5 1771 | -205,85,58.5,5,5,58.5 1772 | -195,85,58.5,5,5,58.5 1773 | -185,85,58.5,5,5,58.5 1774 | -175,85,52.5,5,5,52.5 1775 | -165,84.99998,52.5,5,5,52.5 1776 | -155,84.99999,52.5,5,5,52.5 1777 | -145,84.99998,52.5,5,5,52.5 1778 | -65,84.99999,41.5,5,5,41.5 1779 | -55.00001,85,41.5,5,5,41.5 1780 | -45,85,41.5,5,5,41.5 1781 | -35,85,41.5,5,5,41.5 1782 | -25,84.99999,41.5,5,5,41.5 1783 | -15,85,41.5,5,5,41.5 1784 | -5,85,41.5,5,5,41.5 1785 | 25,85,41.5,5,5,41.5 1786 | 35,85,41.5,5,5,41.5 1787 | 115,85,7.5,5,5,7.5 1788 | 125,85,7.5,5,5,7.5 1789 | 135,85,7.5,5,5,7.5 1790 | 145,85,7.5,5,5,7.5 1791 | 185,85,15.5,5,5,15.5 1792 | 195,85,15.5,5,5,15.5 1793 | 205,85,7,5,5,7 1794 | 215,85,1.5,5,5,1.5 1795 | 225,85,1.5,5,5,1.5 1796 | 235,85,1.5,5,5,1.5 1797 | 245,85,1.5,5,5,1.5 1798 | -245,95,58.5,5,5,58.5 1799 | -235,95,58.5,5,5,58.5 1800 | -225,95,58.5,5,5,58.5 1801 | -215,95,58.5,5,5,58.5 1802 | -205,95,58.5,5,5,58.5 1803 | -185,94.99999,52.5,5,5,52.5 1804 | -175,95,52.5,5,5,52.5 1805 | -165,94.99999,52.5,5,5,52.5 1806 | -155,94.99999,52.5,5,5,52.5 1807 | -145,95,52.5,5,5,52.5 1808 | -135,95,52.5,5,5,52.5 1809 | -75,95,41.5,5,5,41.5 1810 | -65,95,41.5,5,5,41.5 1811 | -55,95,41.5,5,5,41.5 1812 | -45,95,41.5,5,5,41.5 1813 | -35,95,41.5,5,5,41.5 1814 | -25,95,41.5,5,5,41.5 1815 | -15,95,41.5,5,5,41.5 1816 | -5,95,41.5,5,5,41.5 1817 | 25,95,41.5,5,5,41.5 1818 | 35,95,41.5,5,5,41.5 1819 | 45,95,41.5,5,5,41.5 1820 | -235,105,58.5,5,5,58.5 1821 | -225,105,58.5,5,5,58.5 1822 | -215,105,58.5,5,5,58.5 1823 | -195,105,52.5,5,5,52.5 1824 | -185,105,52.5,5,5,52.5 1825 | -175,105,52.5,5,5,52.5 1826 | -165,105,52.5,5,5,52.5 1827 | -155,105,52.5,5,5,52.5 1828 | -145,105,52.5,5,5,52.5 1829 | -135,105,52.5,5,5,52.5 1830 | -85.00001,105,41.5,5,5,41.5 1831 | -75,105,41.5,5,5,41.5 1832 | -65,105,41.5,5,5,41.5 1833 | -55,105,41.5,5,5,41.5 1834 | -45,105,41.5,5,5,41.5 1835 | -34.99999,105,41.5,5,5,41.5 1836 | -25,105,41.5,5,5,41.5 1837 | -15,105,41.5,5,5,41.5 1838 | 35,105,41.5,5,5,41.5 1839 | 45,105,41.5,5,5,41.5 1840 | 54.99999,105,41.5,5,5,41.5 1841 | 375,105,87,5,5,87 1842 | 385,105,87,5,5,87 1843 | 395,105,87,5,5,87 1844 | 405,105,87,5,5,87 1845 | 415,105,87,5,5,87 1846 | -295,115,98.49999,5,5,98.49999 1847 | -285,115,98.49999,5,5,98.49999 1848 | -275,115,98.5,5,5,98.5 1849 | -225,115,58.5,5,5,58.5 1850 | -205,115,52.5,5,5,52.5 1851 | -195,115,52.5,5,5,52.5 1852 | -185,115,52.49999,5,5,52.49999 1853 | -175,115,52.5,5,5,52.5 1854 | -165,115,52.5,5,5,52.5 1855 | -155,115,52.5,5,5,52.5 1856 | -145,115,52.5,5,5,52.5 1857 | -75,115,41.5,5,5,41.5 1858 | -65,115,41.5,5,5,41.5 1859 | -55,115,41.5,5,5,41.5 1860 | -45,115,41.5,5,5,41.5 1861 | -35,115,41.5,5,5,41.5 1862 | -25,115,41.5,5,5,41.5 1863 | -15,115,46.5,5,5,46.5 1864 | 35,115,41.5,5,5,41.5 1865 | 45,115,41.5,5,5,41.5 1866 | 55,115,41.5,5,5,41.5 1867 | 325,115,8.5,5,5,8.5 1868 | 335,115,8.5,5,5,8.5 1869 | 345,115,8.5,5,5,8.5 1870 | 355,115,8.5,5,5,8.5 1871 | 375,115,87,5,5,87 1872 | 385,115,87,5,5,87 1873 | 395,115,87,5,5,87 1874 | 405,115,87,5,5,87 1875 | 415,115,87,5,5,87 1876 | -305,125,98.5,5,5,98.5 1877 | -295,125,98.5,5,5,98.5 1878 | -285,125,98.50001,5,5,98.50001 1879 | -275,125,98.5,5,5,98.5 1880 | -215,125,52.5,5,5,52.5 1881 | -205,125,52.5,5,5,52.5 1882 | -195,125,52.5,5,5,52.5 1883 | -185,125,52.5,5,5,52.5 1884 | -175,125,52.5,5,5,52.5 1885 | -165,125,52.5,5,5,52.5 1886 | -155,125,52.5,5,5,52.5 1887 | -75,125,12.5,5,5,12.5 1888 | -65,125,41.5,5,5,41.5 1889 | -55,125,41.5,5,5,41.5 1890 | -45.00001,125,41.5,5,5,41.5 1891 | -35,125,41.5,5,5,41.5 1892 | -15,125,46.5,5,5,46.5 1893 | -5,125,46.5,5,5,46.5 1894 | 25.00001,125,41.5,5,5,41.5 1895 | 35,125,41.5,5,5,41.5 1896 | 45,125,41.5,5,5,41.5 1897 | 275,125,41.5,5,5,41.5 1898 | 285,125,41.5,5,5,41.5 1899 | 325,125,8.5,5,5,8.5 1900 | 335,125,8.5,5,5,8.5 1901 | 345,125,8.5,5,5,8.5 1902 | 355,125,8.5,5,5,8.5 1903 | 375,125,87,5,5,87 1904 | 385,125,86.99999,5,5,86.99999 1905 | 395,125,87,5,5,87 1906 | 405,125,87,5,5,87 1907 | 415,125,87,5,5,87 1908 | -305,135,98.5,5,5,98.5 1909 | -295,135,98.5,5,5,98.5 1910 | -285,135,98.5,5,5,98.5 1911 | -275,135,98.5,5,5,98.5 1912 | -265,135,98.5,5,5,98.5 1913 | -205,135,52.5,5,5,52.5 1914 | -195,135,52.5,5,5,52.5 1915 | -185,135,52.5,5,5,52.5 1916 | -175,135,52.5,5,5,52.5 1917 | -165,135,52.5,5,5,52.5 1918 | -85,135,12.5,5,5,12.5 1919 | -65,135,12.5,5,5,12.5 1920 | -55,135,41.5,5,5,41.5 1921 | -45,135,41.5,5,5,41.5 1922 | -25,135,46.5,5,5,46.5 1923 | -15,135,46.5,5,5,46.5 1924 | -5,135,46.5,5,5,46.5 1925 | 5,135,46.5,5,5,46.5 1926 | 25,135,41.5,5,5,41.5 1927 | 35,135,41.5,5,5,41.5 1928 | 85,135,6,5,5,6 1929 | 205,135,41.5,5,5,41.5 1930 | 215,135,41.5,5,5,41.5 1931 | 225,135,41.5,5,5,41.5 1932 | 235,135,41.5,5,5,41.5 1933 | 245,135,41.5,5,5,41.5 1934 | 255,135,41.5,5,5,41.5 1935 | 265,135,41.5,5,5,41.5 1936 | 275,135,41.5,5,5,41.5 1937 | 285,135,41.5,5,5,41.5 1938 | 295,135,41.5,5,5,41.5 1939 | 325,135,8.5,5,5,8.5 1940 | 335,135,8.5,5,5,8.5 1941 | 345,135,8.5,5,5,8.5 1942 | 355,135,8.5,5,5,8.5 1943 | 365,135,8.5,5,5,8.5 1944 | 375,135,87,5,5,87 1945 | 385,135,86.99999,5,5,86.99999 1946 | 395,135,87,5,5,87 1947 | 405,135,87,5,5,87 1948 | 415,135,87,5,5,87 1949 | -305,145,98.5,5,5,98.5 1950 | -295,145,98.5,5,5,98.5 1951 | -285,145,98.5,5,5,98.5 1952 | -275,145,98.5,5,5,98.5 1953 | -255,145,22,5,5,22 1954 | -245,145,22,5,5,22 1955 | -195,145,52.5,5,5,52.5 1956 | -185,145,52.5,5,5,52.5 1957 | -175,145,52.5,5,5,52.5 1958 | -95,145,12.5,5,5,12.5 1959 | -55,145,12.5,5,5,12.5 1960 | -45.00001,145,46.5,5,5,46.5 1961 | -35,145,46.5,5,5,46.5 1962 | -25,145,46.5,5,5,46.5 1963 | -15,145,46.5,5,5,46.5 1964 | -5,145,46.5,5,5,46.5 1965 | 5,145,46.5,5,5,46.5 1966 | 15,145,46.5,5,5,46.5 1967 | 75,145,1.5,5,5,1.5 1968 | 85,145,6,5,5,6 1969 | 95,145,6,5,5,6 1970 | 195,145,41.5,5,5,41.5 1971 | 205,145,41.5,5,5,41.5 1972 | 215,145,41.5,5,5,41.5 1973 | 225,145,41.5,5,5,41.5 1974 | 235,145,41.5,5,5,41.5 1975 | 245,145,41.5,5,5,41.5 1976 | 255,145,41.5,5,5,41.5 1977 | 265,145,41.5,5,5,41.5 1978 | 275,145,41.5,5,5,41.5 1979 | 285,145,41.5,5,5,41.5 1980 | 295,145,41.5,5,5,41.5 1981 | 325,145,8.5,5,5,8.5 1982 | 335,145,8.5,5,5,8.5 1983 | 365,145,8.5,5,5,8.5 1984 | 375,145,87,5,5,87 1985 | 385,145,87,5,5,87 1986 | 395,145,87,5,5,87 1987 | 405,145,87,5,5,87 1988 | 415,145,87,5,5,87 1989 | -305,155,98.5,5,5,98.5 1990 | -295,155,98.50002,5,5,98.50002 1991 | -285,155,98.5,5,5,98.5 1992 | -265,155,22,5,5,22 1993 | -255,155,22,5,5,22 1994 | -245,155,22,5,5,22 1995 | -235,155,22,5,5,22 1996 | -185,155,52.5,5,5,52.5 1997 | -115,155,77,5,5,77 1998 | -105,155,77,5,5,77 1999 | -95,155,77,5,5,77 2000 | -85,155,12.5,5,5,12.5 2001 | -65,155,12.5,5,5,12.5 2002 | -45,155,46.5,5,5,46.5 2003 | -35,155,46.5,5,5,46.5 2004 | -25,155,46.5,5,5,46.5 2005 | -15,155,46.5,5,5,46.5 2006 | -5,155,46.5,5,5,46.5 2007 | 5,155,46.5,5,5,46.5 2008 | 65,155,1.5,5,5,1.5 2009 | 75,155,1.5,5,5,1.5 2010 | 85,155,1.5,5,5,1.5 2011 | 95,155,6,5,5,6 2012 | 105,155,6,5,5,6 2013 | 195,155,41.5,5,5,41.5 2014 | 205,155,41.5,5,5,41.5 2015 | 215,155,41.5,5,5,41.5 2016 | 225,155,41.5,5,5,41.5 2017 | 235,155,41.5,5,5,41.5 2018 | 245,155,41.5,5,5,41.5 2019 | 255,155,41.5,5,5,41.5 2020 | 265,155,41.5,5,5,41.5 2021 | 275,155,41.5,5,5,41.5 2022 | 285,155,41.5,5,5,41.5 2023 | 295,155,41.5,5,5,41.5 2024 | 315,155,8.5,5,5,8.5 2025 | 325,155,8.5,5,5,8.5 2026 | 335,155,8.5,5,5,8.5 2027 | 365,155,8.5,5,5,8.5 2028 | 375,155,87,5,5,87 2029 | 385,155,87.00001,5,5,87.00001 2030 | 395,155,87,5,5,87 2031 | 405,155,87,5,5,87 2032 | 415,155,87,5,5,87 2033 | -305,165,98.5,5,5,98.5 2034 | -295,165,98.5,5,5,98.5 2035 | -275,165,22,5,5,22 2036 | -265,165,22,5,5,22 2037 | -255,165,22,5,5,22 2038 | -245,165,22,5,5,22 2039 | -235,165,22,5,5,22 2040 | -225,165,22,5,5,22 2041 | -125,165,77,5,5,77 2042 | -115,165,77,5,5,77 2043 | -105,165,77,5,5,77 2044 | -95,165,77,5,5,77 2045 | -85.00001,165,77,5,5,77 2046 | -75.00001,165,12.5,5,5,12.5 2047 | -65,165,75.5,5,5,75.5 2048 | -55,165,75.5,5,5,75.5 2049 | -45,165,46.5,5,5,46.5 2050 | -35,165,46.5,5,5,46.5 2051 | -25,165,46.5,5,5,46.5 2052 | -15,165,46.5,5,5,46.5 2053 | -5,165,46.5,5,5,46.5 2054 | 54.99999,165,1.5,5,5,1.5 2055 | 65,165,1.5,5,5,1.5 2056 | 75,165,1.5,5,5,1.5 2057 | 85,165,1.5,5,5,1.5 2058 | 95,165,1.5,5,5,1.5 2059 | 105,165,6,5,5,6 2060 | 115,165,6,5,5,6 2061 | 195,165,41.5,5,5,41.5 2062 | 205,165,41.5,5,5,41.5 2063 | 215,165,41.5,5,5,41.5 2064 | 225,165,41.5,5,5,41.5 2065 | 235,165,41.5,5,5,41.5 2066 | 245,165,41.5,5,5,41.5 2067 | 255,165,41.5,5,5,41.5 2068 | 265,165,41.5,5,5,41.5 2069 | 275,165,41.5,5,5,41.5 2070 | 285,165,41.5,5,5,41.5 2071 | 295,165,41.5,5,5,41.5 2072 | 315,165,8.5,5,5,8.5 2073 | 325,165,8.5,5,5,8.5 2074 | 335,165,8.5,5,5,8.5 2075 | 345,165,8.5,5,5,8.5 2076 | 355,165,8.5,5,5,8.5 2077 | 365,165,8.5,5,5,8.5 2078 | 385,165,87,5,5,87 2079 | 395,165,87,5,5,87 2080 | 405,165,87,5,5,87 2081 | 415,165,87,5,5,87 2082 | -305,175,22,5,5,22 2083 | -285,175,22,5,5,22 2084 | -275,175,22,5,5,22 2085 | -265,175,22,5,5,22 2086 | -255,175,22,5,5,22 2087 | -245,175,22,5,5,22 2088 | -235,175,22,5,5,22 2089 | -225,175,22,5,5,22 2090 | -215,175,22,5,5,22 2091 | -135,175,77,5,5,77 2092 | -125,175,77,5,5,77 2093 | -115,175,77,5,5,77 2094 | -105,175,77,5,5,77 2095 | -94.99999,175,77,5,5,77 2096 | -84.99999,175,77,5,5,77 2097 | -75,175,77,5,5,77 2098 | -65,175,75.5,5,5,75.5 2099 | -55,175,75.5,5,5,75.5 2100 | -45,175,75.5,5,5,75.5 2101 | -35,175,46.5,5,5,46.5 2102 | -25,175,46.5,5,5,46.5 2103 | -15,175,46.5,5,5,46.5 2104 | 45,175,1.5,5,5,1.5 2105 | 55.00001,175,1.5,5,5,1.5 2106 | 65.00002,175,1.5,5,5,1.5 2107 | 75,175,1.5,5,5,1.5 2108 | 85,175,1.5,5,5,1.5 2109 | 95.00001,175,1.5,5,5,1.5 2110 | 105,175,1.5,5,5,1.5 2111 | 115,175,6,5,5,6 2112 | 125,175,6,5,5,6 2113 | 205,175,41.5,5,5,41.5 2114 | 215,175,41.5,5,5,41.5 2115 | 225,175,41.5,5,5,41.5 2116 | 235,175,41.5,5,5,41.5 2117 | 245,175,41.5,5,5,41.5 2118 | 255,175,41.5,5,5,41.5 2119 | 265,175,41.5,5,5,41.5 2120 | 275,175,41.5,5,5,41.5 2121 | 285,175,41.5,5,5,41.5 2122 | 295,175,41.5,5,5,41.5 2123 | 315,175,8.5,5,5,8.5 2124 | 325,175,8.5,5,5,8.5 2125 | 335,175,8.5,5,5,8.5 2126 | 345,175,8.499999,5,5,8.499999 2127 | 355,175,8.5,5,5,8.5 2128 | 365,175,8.5,5,5,8.5 2129 | 395,175,86.99999,5,5,86.99999 2130 | 405,175,87,5,5,87 2131 | 415,175,87,5,5,87 2132 | 425,175,87,5,5,87 2133 | -295,185,22,5,5,22 2134 | -285,185,22,5,5,22 2135 | -275,185,22,5,5,22 2136 | -265,185,22,5,5,22 2137 | -255,185,22,5,5,22 2138 | -245,185,22,5,5,22 2139 | -235,185,22,5,5,22 2140 | -225,185,22,5,5,22 2141 | -215,185,22,5,5,22 2142 | -135,185,77,5,5,77 2143 | -125,185,77,5,5,77 2144 | -115,185,77,5,5,77 2145 | -105,185,77,5,5,77 2146 | -95,185,77,5,5,77 2147 | -85,185,77,5,5,77 2148 | -75,185,77,5,5,77 2149 | -65,185,77.00001,5,5,77.00001 2150 | -55,185,75.5,5,5,75.5 2151 | -25,185,46.5,5,5,46.5 2152 | 55,185,1.5,5,5,1.5 2153 | 65,185,1.5,5,5,1.5 2154 | 74.99999,185,1.5,5,5,1.5 2155 | 85,185,1.5,5,5,1.5 2156 | 95.00001,185,1.5,5,5,1.5 2157 | 105,185,1.5,5,5,1.5 2158 | 115,185,1.5,5,5,1.5 2159 | 125,185,6,5,5,6 2160 | 135,185,6,5,5,6 2161 | 215,185,41.5,5,5,41.5 2162 | 225,185,41.5,5,5,41.5 2163 | 235,185,41.5,5,5,41.5 2164 | 245,185,41.5,5,5,41.5 2165 | 255,185,41.5,5,5,41.5 2166 | 265,185,41.5,5,5,41.5 2167 | 275,185,41.5,5,5,41.5 2168 | 285,185,41.5,5,5,41.5 2169 | 295,185,41.5,5,5,41.5 2170 | 305,185,41.5,5,5,41.5 2171 | 315,185,8.5,5,5,8.5 2172 | 325,185,8.5,5,5,8.5 2173 | 335,185,8.5,5,5,8.5 2174 | 345,185,8.5,5,5,8.5 2175 | 355,185,8.499999,5,5,8.499999 2176 | 365,185,8.5,5,5,8.5 2177 | -285,195,22,5,5,22 2178 | -275,195,22,5,5,22 2179 | -265,195,22,5,5,22 2180 | -255,195,22,5,5,22 2181 | -245,195,22,5,5,22 2182 | -235,195,22,5,5,22 2183 | -225,195,22,5,5,22 2184 | -125,195,77,5,5,77 2185 | -115,195,77,5,5,77 2186 | -105,195,77,5,5,77 2187 | -95,195,77,5,5,77 2188 | -85.00001,195,77,5,5,77 2189 | -75,195,77,5,5,77 2190 | -65,195,77,5,5,77 2191 | 25.00002,195,1.5,5,5,1.5 2192 | 65,195,1.5,5,5,1.5 2193 | 75,195,1.5,5,5,1.5 2194 | 85,195,1.5,5,5,1.5 2195 | 95,195,1.5,5,5,1.5 2196 | 105,195,1.5,5,5,1.5 2197 | 115,195,1.5,5,5,1.5 2198 | 125,195,1.5,5,5,1.5 2199 | 135,195,6,5,5,6 2200 | 145,195,6,5,5,6 2201 | 225,195,41.5,5,5,41.5 2202 | 235,195,41.5,5,5,41.5 2203 | 245,195,41.5,5,5,41.5 2204 | 255,195,41.5,5,5,41.5 2205 | 265,195,41.5,5,5,41.5 2206 | 275,195,41.5,5,5,41.5 2207 | 285,195,41.5,5,5,41.5 2208 | 295,195,41.5,5,5,41.5 2209 | 305,195,41.5,5,5,41.5 2210 | 325,195,8.5,5,5,8.5 2211 | 335,195,8.5,5,5,8.5 2212 | 345,195,8.5,5,5,8.5 2213 | 355,195,8.5,5,5,8.5 2214 | 365,195,8.5,5,5,8.5 2215 | -275,205,22,5,5,22 2216 | -265,205,22,5,5,22 2217 | -255,205,22,5,5,22 2218 | -245,205,22,5,5,22 2219 | -235,205,22,5,5,22 2220 | -115,205,77,5,5,77 2221 | -105,205,77,5,5,77 2222 | -95,205,77,5,5,77 2223 | -85,205,77,5,5,77 2224 | -75,205,77,5,5,77 2225 | -65,205,77,5,5,77 2226 | 15,205,1.5,5,5,1.5 2227 | 25.00002,205,1.5,5,5,1.5 2228 | 35,205,1.5,5,5,1.5 2229 | 74.99999,205,1.5,5,5,1.5 2230 | 85,205,1.5,5,5,1.5 2231 | 95,205,1.5,5,5,1.5 2232 | 105,205,1.5,5,5,1.5 2233 | 115,205,1.5,5,5,1.5 2234 | 125,205,1.5,5,5,1.5 2235 | 135,205,1.5,5,5,1.5 2236 | 145,205,6,5,5,6 2237 | 155,205,6,5,5,6 2238 | 235,205,41.5,5,5,41.5 2239 | 245,205,41.5,5,5,41.5 2240 | 255,205,41.5,5,5,41.5 2241 | 265,205,41.5,5,5,41.5 2242 | 275,205,41.5,5,5,41.5 2243 | 285,205,41.5,5,5,41.5 2244 | 295,205,41.5,5,5,41.5 2245 | 305,205,41.5,5,5,41.5 2246 | 325,205,8.5,5,5,8.5 2247 | 335,205,8.5,5,5,8.5 2248 | 345,205,8.5,5,5,8.5 2249 | 355,205,8.5,5,5,8.5 2250 | 405,205,2.078876,5,5,2.078876 2251 | -265,215,22,5,5,22 2252 | -255,215,22,5,5,22 2253 | -245,215,22,5,5,22 2254 | -105,215,77,5,5,77 2255 | -95,215,77,5,5,77 2256 | -85,215,77,5,5,77 2257 | -75,215,76.99999,5,5,76.99999 2258 | 5.000015,215,1.5,5,5,1.5 2259 | 15.00002,215,1.5,5,5,1.5 2260 | 25.00002,215,1.5,5,5,1.5 2261 | 35.00001,215,1.5,5,5,1.5 2262 | 45.00002,215,1.5,5,5,1.5 2263 | 85,215,1.5,5,5,1.5 2264 | 95,215,1.5,5,5,1.5 2265 | 105,215,1.5,5,5,1.5 2266 | 115,215,1.5,5,5,1.5 2267 | 125,215,1.5,5,5,1.5 2268 | 135,215,1.5,5,5,1.5 2269 | 145,215,1.5,5,5,1.5 2270 | 245,215,41.5,5,5,41.5 2271 | 255,215,41.5,5,5,41.5 2272 | 265,215,41.5,5,5,41.5 2273 | 275,215,41.5,5,5,41.5 2274 | 285,215,41.5,5,5,41.5 2275 | 295,215,41.5,5,5,41.5 2276 | 305,215,41.5,5,5,41.5 2277 | 325,215,8.5,5,5,8.5 2278 | 335,215,8.5,5,5,8.5 2279 | 345,215,8.5,5,5,8.5 2280 | -185,225,69,5,5,69 2281 | -175,225,69,5,5,69 2282 | -95,225,77.00001,5,5,77.00001 2283 | -85,225,77,5,5,77 2284 | 5.000015,225,1.5,5,5,1.5 2285 | 15.00002,225,1.5,5,5,1.5 2286 | 25.00002,225,1.5,5,5,1.5 2287 | 35.00002,225,1.5,5,5,1.5 2288 | 45.00001,225,1.5,5,5,1.5 2289 | 55.00002,225,1.5,5,5,1.5 2290 | 95,225,1.5,5,5,1.5 2291 | 105,225,1.5,5,5,1.5 2292 | 115,225,1.5,5,5,1.5 2293 | 125,225,1.5,5,5,1.5 2294 | 135,225,1.5,5,5,1.5 2295 | 255,225,41.5,5,5,41.5 2296 | 265,225,41.5,5,5,41.5 2297 | 275,225,41.5,5,5,41.5 2298 | 285,225,41.5,5,5,41.5 2299 | 295,225,41.5,5,5,41.5 2300 | 305,225,41.5,5,5,41.5 2301 | 335,225,8.5,5,5,8.5 2302 | -185,235,69,5,5,69 2303 | -175,235,69,5,5,69 2304 | -165,235,69,5,5,69 2305 | 15,235,1.5,5,5,1.5 2306 | 25,235,1.5,5,5,1.5 2307 | 35.00001,235,1.5,5,5,1.5 2308 | 45.00001,235,1.5,5,5,1.5 2309 | 55.00001,235,1.5,5,5,1.5 2310 | 65.00001,235,1.5,5,5,1.5 2311 | 105,235,1.5,5,5,1.5 2312 | 115,235,1.5,5,5,1.5 2313 | 125,235,1.5,5,5,1.5 2314 | 175,235,30,5,5,30 2315 | 185,235,30,5,5,30 2316 | 265,235,41.5,5,5,41.5 2317 | 275,235,41.5,5,5,41.5 2318 | 285,235,41.5,5,5,41.5 2319 | 295,235,41.5,5,5,41.5 2320 | 305,235,41.5,5,5,41.5 2321 | -185,245,69.00001,5,5,69.00001 2322 | -175,245,69,5,5,69 2323 | -165,245,69,5,5,69 2324 | -155,245,69,5,5,69 2325 | 25,245,1.5,5,5,1.5 2326 | 35.00001,245,1.5,5,5,1.5 2327 | 45,245,1.5,5,5,1.5 2328 | 55,245,1.5,5,5,1.5 2329 | 65.00001,245,1.5,5,5,1.5 2330 | 75,245,1.5,5,5,1.5 2331 | 115,245,1.5,5,5,1.5 2332 | 165,245,30,5,5,30 2333 | 175,245,30,5,5,30 2334 | 185,245,30,5,5,30 2335 | 195,245,30,5,5,30 2336 | 275,245,41.5,5,5,41.5 2337 | 285,245,41.5,5,5,41.5 2338 | 295,245,41.5,5,5,41.5 2339 | 305,245,41.5,5,5,41.5 2340 | 315,245,41.5,5,5,41.5 2341 | -195,255,69,5,5,69 2342 | -185,255,69,5,5,69 2343 | -175,255,69,5,5,69 2344 | -165,255,69,5,5,69 2345 | -155,255,69,5,5,69 2346 | -145,255,69,5,5,69 2347 | 35.00001,255,1.5,5,5,1.5 2348 | 45,255,1.5,5,5,1.5 2349 | 55,255,1.5,5,5,1.5 2350 | 65,255,1.5,5,5,1.5 2351 | 75,255,1.5,5,5,1.5 2352 | 85,255,1.5,5,5,1.5 2353 | 155,255,30,5,5,30 2354 | 165,255,30,5,5,30 2355 | 175,255,30,5,5,30 2356 | 185,255,30,5,5,30 2357 | 195,255,30,5,5,30 2358 | 205,255,30,5,5,30 2359 | 285,255,41.5,5,5,41.5 2360 | 295,255,41.5,5,5,41.5 2361 | 305,255,41.5,5,5,41.5 2362 | -205,265,69,5,5,69 2363 | -195,265,69,5,5,69 2364 | -185,265,69,5,5,69 2365 | -175,265,69,5,5,69 2366 | -165,265,69,5,5,69 2367 | -155,265,69,5,5,69 2368 | -145,265,69,5,5,69 2369 | -135,265,69,5,5,69 2370 | 45,265,1.5,5,5,1.5 2371 | 55,265,1.5,5,5,1.5 2372 | 65,265,1.5,5,5,1.5 2373 | 75,265,1.5,5,5,1.5 2374 | 85,265,1.5,5,5,1.5 2375 | 95,265,1.5,5,5,1.5 2376 | 145,265,30,5,5,30 2377 | 155,265,30,5,5,30 2378 | 165,265,30,5,5,30 2379 | 175,265,30,5,5,30 2380 | 185,265,30,5,5,30 2381 | 195,265,30,5,5,30 2382 | 205,265,30,5,5,30 2383 | 215,265,30,5,5,30 2384 | 295,265,41.5,5,5,41.5 2385 | -205,275,69,5,5,69 2386 | -195,275,69,5,5,69 2387 | -185,275,69,5,5,69 2388 | -175,275,69,5,5,69 2389 | -165,275,69,5,5,69 2390 | -155,275,69,5,5,69 2391 | -145,275,69,5,5,69 2392 | 55,275,1.5,5,5,1.5 2393 | 65.00001,275,1.5,5,5,1.5 2394 | 75,275,1.5,5,5,1.5 2395 | 85,275,1.5,5,5,1.5 2396 | 135,275,30,5,5,30 2397 | 145,275,30,5,5,30 2398 | 155,275,30,5,5,30 2399 | 165,275,30,5,5,30 2400 | 175,275,30,5,5,30 2401 | 185,275,30,5,5,30 2402 | 195,275,30,5,5,30 2403 | 205,275,30,5,5,30 2404 | 215,275,30,5,5,30 2405 | 225,275,30,5,5,30 2406 | -205,285,69,5,5,69 2407 | -195,285,69,5,5,69 2408 | -185,285,69,5,5,69 2409 | -175,285,69,5,5,69 2410 | -165,285,69,5,5,69 2411 | -155,285,69,5,5,69 2412 | 65,285,1.5,5,5,1.5 2413 | 75,285,1.5,5,5,1.5 2414 | 125,285,85.99999,5,5,85.99999 2415 | 135,285,86,5,5,86 2416 | 145,285,30,5,5,30 2417 | 155,285,30,5,5,30 2418 | 165,285,30,5,5,30 2419 | 175,285,30,5,5,30 2420 | 185,285,30,5,5,30 2421 | 195,285,30,5,5,30 2422 | 205,285,30,5,5,30 2423 | 215,285,30,5,5,30 2424 | 225,285,30,5,5,30 2425 | 235,285,30,5,5,30 2426 | 325,285,2.446928,5,5,2.446928 2427 | -215,295,69,5,5,69 2428 | -205,295,69,5,5,69 2429 | -195,295,69,5,5,69 2430 | -185,295,69,5,5,69 2431 | -175,295,69,5,5,69 2432 | -165,295,69,5,5,69 2433 | 15,295,30,5,5,30 2434 | 115,295,86,5,5,86 2435 | 125,295,86,5,5,86 2436 | 135,295,86,5,5,86 2437 | 145,295,86,5,5,86 2438 | 155,295,30,5,5,30 2439 | 165,295,30,5,5,30 2440 | 175,295,30,5,5,30 2441 | 185,295,30,5,5,30 2442 | 195,295,30,5,5,30 2443 | 205,295,30,5,5,30 2444 | 215,295,30,5,5,30 2445 | 225,295,30,5,5,30 2446 | 235,295,30,5,5,30 2447 | 245,295,30,5,5,30 2448 | -215,305,69,5,5,69 2449 | -205,305,68.99999,5,5,68.99999 2450 | -195,305,69,5,5,69 2451 | -185,305,69,5,5,69 2452 | 5,305,30,5,5,30 2453 | 15,305,30,5,5,30 2454 | 25,305,30,5,5,30 2455 | 105,305,86,5,5,86 2456 | 115,305,86,5,5,86 2457 | 125,305,86,5,5,86 2458 | 135,305,86,5,5,86 2459 | 145,305,86,5,5,86 2460 | 155,305,86,5,5,86 2461 | 165,305,30,5,5,30 2462 | 175,305,30,5,5,30 2463 | 185,305,30,5,5,30 2464 | 195,305,30,5,5,30 2465 | 205,305,30,5,5,30 2466 | 215,305,30,5,5,30 2467 | 225,305,30,5,5,30 2468 | 235,305,30,5,5,30 2469 | 245,305,30,5,5,30 2470 | -215,315,69,5,5,69 2471 | -205,315,69,5,5,69 2472 | -195,315,69,5,5,69 2473 | -95,315,66.5,5,5,66.5 2474 | -85,315,66.5,5,5,66.5 2475 | -5,315,30,5,5,30 2476 | 5,315,30,5,5,30 2477 | 15,315,30,5,5,30 2478 | 25,315,30,5,5,30 2479 | 35,315,30,5,5,30 2480 | 95,315,86,5,5,86 2481 | 105,315,86,5,5,86 2482 | 115,315,86.00001,5,5,86.00001 2483 | 125,315,85.99999,5,5,85.99999 2484 | 135,315,86,5,5,86 2485 | 145,315,86,5,5,86 2486 | 155,315,30,5,5,30 2487 | 165,315,30,5,5,30 2488 | 175,315,30,5,5,30 2489 | 185,315,30,5,5,30 2490 | 195,315,30,5,5,30 2491 | 205,315,30,5,5,30 2492 | 215,315,30,5,5,30 2493 | 225,315,30,5,5,30 2494 | 235,315,30,5,5,30 2495 | -225,325,69,5,5,69 2496 | -215,325,69,5,5,69 2497 | -205,325,69,5,5,69 2498 | -105,325,66.5,5,5,66.5 2499 | -95,325,66.5,5,5,66.5 2500 | -85,325,66.5,5,5,66.5 2501 | -75,325,66.5,5,5,66.5 2502 | -15,325,30,5,5,30 2503 | -5,325,30,5,5,30 2504 | 5,325,30,5,5,30 2505 | 15,325,30,5,5,30 2506 | 25,325,30,5,5,30 2507 | 35.00001,325,30,5,5,30 2508 | 85,325,86,5,5,86 2509 | 95,325,86,5,5,86 2510 | 105,325,86,5,5,86 2511 | 115,325,86,5,5,86 2512 | 125,325,86,5,5,86 2513 | 135,325,86,5,5,86 2514 | 145,325,14,5,5,14 2515 | 155,325,14,5,5,14 2516 | 165,325,30,5,5,30 2517 | 175,325,30,5,5,30 2518 | 185,325,30,5,5,30 2519 | 195,325,30,5,5,30 2520 | 205,325,30,5,5,30 2521 | 215,325,30,5,5,30 2522 | 225,325,30,5,5,30 2523 | -225,335,69,5,5,69 2524 | -215,335,69,5,5,69 2525 | -115,335,66.5,5,5,66.5 2526 | -105,335,66.5,5,5,66.5 2527 | -95,335,66.5,5,5,66.5 2528 | -85,335,66.5,5,5,66.5 2529 | -75,335,66.5,5,5,66.5 2530 | -65,335,66.5,5,5,66.5 2531 | -5,335,30,5,5,30 2532 | 5,335,30,5,5,30 2533 | 15.00002,335,30,5,5,30 2534 | 25,335,30,5,5,30 2535 | 75,335,14,5,5,14 2536 | 85,335,14,5,5,14 2537 | 95,335,86,5,5,86 2538 | 105,335,86,5,5,86 2539 | 115,335,86,5,5,86 2540 | 125,335,86,5,5,86 2541 | 135,335,14,5,5,14 2542 | 145,335,14,5,5,14 2543 | 155,335,14,5,5,14 2544 | 165,335,14,5,5,14 2545 | 175,335,30,5,5,30 2546 | 185,335,30,5,5,30 2547 | 195,335,30,5,5,30 2548 | 205,335,30,5,5,30 2549 | 215,335,30,5,5,30 2550 | -225,345,69,5,5,69 2551 | -125,345,52,5,5,52 2552 | -115,345,66.5,5,5,66.5 2553 | -105,345,66.5,5,5,66.5 2554 | -95,345,66.5,5,5,66.5 2555 | -85,345,66.5,5,5,66.5 2556 | -75,345,66.5,5,5,66.5 2557 | 5,345,30,5,5,30 2558 | 15,345,30,5,5,30 2559 | 65,345,14,5,5,14 2560 | 75,345,14,5,5,14 2561 | 85,345,14,5,5,14 2562 | 94.99999,345,14,5,5,14 2563 | 105,345,86,5,5,86 2564 | 115,345,86,5,5,86 2565 | 125,345,14,5,5,14 2566 | 135,345,14,5,5,14 2567 | 145,345,14,5,5,14 2568 | 155,345,14,5,5,14 2569 | 165,345,14,5,5,14 2570 | 175,345,14,5,5,14 2571 | 185,345,30,5,5,30 2572 | 195,345,30,5,5,30 2573 | 205,345,30,5,5,30 2574 | -135,355,52,5,5,52 2575 | -125,355,52,5,5,52 2576 | -115,355,52,5,5,52 2577 | -105,355,66.5,5,5,66.5 2578 | -95,355,66.5,5,5,66.5 2579 | -85,355,66.5,5,5,66.5 2580 | 55.00002,355,14,5,5,14 2581 | 65.00001,355,14,5,5,14 2582 | 75,355,14,5,5,14 2583 | 85,355,14,5,5,14 2584 | 95,355,14,5,5,14 2585 | 105,355,14,5,5,14 2586 | 115,355,14,5,5,14 2587 | 125,355,55.5,5,5,55.5 2588 | 135,355,14,5,5,14 2589 | 145,355,14,5,5,14 2590 | 155,355,14,5,5,14 2591 | 165,355,14,5,5,14 2592 | 175,355,14,5,5,14 2593 | 185,355,14,5,5,14 2594 | 195,355,30,5,5,30 2595 | -155,365,52,5,5,52 2596 | -145,365,52,5,5,52 2597 | -135,365,52,5,5,52 2598 | -125,365,52,5,5,52 2599 | -115,365,52,5,5,52 2600 | -105,365,52,5,5,52 2601 | -45,365,47,5,5,47 2602 | -35,365,47,5,5,47 2603 | 45.00001,365,14,5,5,14 2604 | 55.00002,365,14,5,5,14 2605 | 65.00001,365,14,5,5,14 2606 | 75,365,14,5,5,14 2607 | 85,365,14,5,5,14 2608 | 95,365,14,5,5,14 2609 | 105,365,14,5,5,14 2610 | 115,365,55.5,5,5,55.5 2611 | 125,365,55.5,5,5,55.5 2612 | 135,365,55.5,5,5,55.5 2613 | 145,365,14,5,5,14 2614 | 155,365,14,5,5,14 2615 | 165,365,14,5,5,14 2616 | 175,365,14,5,5,14 2617 | 185,365,14,5,5,14 2618 | 495,365,8,5,5,8 2619 | -155,375,52,5,5,52 2620 | -145,375,52,5,5,52 2621 | -135,375,52,5,5,52 2622 | -125,375,52,5,5,52 2623 | -115,375,52,5,5,52 2624 | -105,375,52,5,5,52 2625 | -55,375,47,5,5,47 2626 | -45,375,47,5,5,47 2627 | -35.00001,375,47,5,5,47 2628 | -25.00002,375,47,5,5,47 2629 | 45.00001,375,14,5,5,14 2630 | 55.00001,375,14,5,5,14 2631 | 65.00001,375,14,5,5,14 2632 | 75,375,14,5,5,14 2633 | 85,375,14,5,5,14 2634 | 95,375,14,5,5,14 2635 | 105,375,55.5,5,5,55.5 2636 | 115,375,55.5,5,5,55.5 2637 | 125,375,55.5,5,5,55.5 2638 | 135,375,55.5,5,5,55.5 2639 | 145,375,55.5,5,5,55.5 2640 | 155,375,14,5,5,14 2641 | 165,375,14,5,5,14 2642 | 175,375,14,5,5,14 2643 | 485,375,8,5,5,8 2644 | 495,375,8,5,5,8 2645 | -165,385,41.5,5,5,41.5 2646 | -145,385,52,5,5,52 2647 | -135,385,52,5,5,52 2648 | -125,385,52,5,5,52 2649 | -115,385,52,5,5,52 2650 | -95,385,8.5,5,5,8.5 2651 | -85,385,8.5,5,5,8.5 2652 | -65,385,47,5,5,47 2653 | -55,385,47,5,5,47 2654 | -45,385,47,5,5,47 2655 | -35,385,47,5,5,47 2656 | -25,385,47,5,5,47 2657 | 55.00002,385,14,5,5,14 2658 | 65.00002,385,14,5,5,14 2659 | 75.00001,385,14,5,5,14 2660 | 85,385,14,5,5,14 2661 | 95,385,55.5,5,5,55.5 2662 | 105,385,55.5,5,5,55.5 2663 | 115,385,55.5,5,5,55.5 2664 | 125,385,55.5,5,5,55.5 2665 | 135,385,55.5,5,5,55.5 2666 | 145,385,55.5,5,5,55.5 2667 | 155,385,55.5,5,5,55.5 2668 | 165,385,14,5,5,14 2669 | 475,385,8,5,5,8 2670 | 485,385,8,5,5,8 2671 | 495,385,8,5,5,8 2672 | -175,395,41.5,5,5,41.5 2673 | -165,395,41.5,5,5,41.5 2674 | -155,395,41.5,5,5,41.5 2675 | -135,395,52,5,5,52 2676 | -125,395,52,5,5,52 2677 | -95,395,8.5,5,5,8.5 2678 | -85,395,8.5,5,5,8.5 2679 | -75,395,8.5,5,5,8.5 2680 | -54.99999,395,47,5,5,47 2681 | -45,395,47,5,5,47 2682 | -35,395,47,5,5,47 2683 | 65.00001,395,14,5,5,14 2684 | 75.00003,394.9999,14,5,5,14 2685 | 85,395,14,5,5,14 2686 | 95,395,55.5,5,5,55.5 2687 | 105,395,55.5,5,5,55.5 2688 | 115,395,55.5,5,5,55.5 2689 | 125,395,55.5,5,5,55.5 2690 | 135,395,55.5,5,5,55.5 2691 | 145,395,55.5,5,5,55.5 2692 | 155,395,14,5,5,14 2693 | 455,395,8,5,5,8 2694 | 465,395,8,5,5,8 2695 | 475,395,8,5,5,8 2696 | 485,395,8,5,5,8 2697 | 495,395,8,5,5,8 2698 | -185,405,41.5,5,5,41.5 2699 | -175,405,41.5,5,5,41.5 2700 | -165,405,41.5,5,5,41.5 2701 | -155,405,41.5,5,5,41.5 2702 | -145,405,41.5,5,5,41.5 2703 | -105,405,40,5,5,40 2704 | -95,405,40,5,5,40 2705 | -85,405,8.5,5,5,8.5 2706 | -75,405,8.5,5,5,8.5 2707 | -65,405,8.5,5,5,8.5 2708 | -55,405,47,5,5,47 2709 | -45,405,47,5,5,47 2710 | 5,405,16.5,5,5,16.5 2711 | 95,405,14,5,5,14 2712 | 105,405,55.5,5,5,55.5 2713 | 115,405,55.5,5,5,55.5 2714 | 125,405,55.5,5,5,55.5 2715 | 135,405,55.5,5,5,55.5 2716 | 145,405,14,5,5,14 2717 | 425,405,8,5,5,8 2718 | 445,405,8,5,5,8 2719 | 455,405,8,5,5,8 2720 | 465,405,8,5,5,8 2721 | 475,405,8,5,5,8 2722 | 485,405,8,5,5,8 2723 | 495,405,8,5,5,8 2724 | -195,415,41.5,5,5,41.5 2725 | -185,415,41.5,5,5,41.5 2726 | -175,415,41.5,5,5,41.5 2727 | -165,415,41.5,5,5,41.5 2728 | -155,415,41.5,5,5,41.5 2729 | -145,415,41.5,5,5,41.5 2730 | -135,415,41.5,5,5,41.5 2731 | -115,415,40,5,5,40 2732 | -105,415,40,5,5,40 2733 | -95,415,40,5,5,40 2734 | -85,415,40,5,5,40 2735 | -75,415,8.5,5,5,8.5 2736 | -65,415,8.5,5,5,8.5 2737 | -55,415,8.5,5,5,8.5 2738 | -5,415,16.5,5,5,16.5 2739 | 5,415,16.5,5,5,16.5 2740 | 15,415,16.5,5,5,16.5 2741 | 105,415,14,5,5,14 2742 | 115,415,55.5,5,5,55.5 2743 | 125,415,55.5,5,5,55.5 2744 | 135,415,14,5,5,14 2745 | 265,415,3.850401,5,5,3.850401 2746 | 415,415,8,5,5,8 2747 | 424.9999,415,8,5,5,8 2748 | 435,415,8,5,5,8 2749 | 445,415,8,5,5,8 2750 | 455,415,8,5,5,8 2751 | 465,415,8,5,5,8 2752 | 475,415,8,5,5,8 2753 | 485,415,8,5,5,8 2754 | 495,415,8,5,5,8 2755 | -205,425,28.5,5,5,28.5 2756 | -185,425,41.5,5,5,41.5 2757 | -175,425,41.5,5,5,41.5 2758 | -165,425,41.5,5,5,41.5 2759 | -155,425,41.5,5,5,41.5 2760 | -145,425,41.5,5,5,41.5 2761 | -125,425,40,5,5,40 2762 | -115,425,40,5,5,40 2763 | -105,425,40,5,5,40 2764 | -95,425,40,5,5,40 2765 | -85,425,40,5,5,40 2766 | -75,425,40,5,5,40 2767 | -65,425,8.500001,5,5,8.500001 2768 | -15,425,16.5,5,5,16.5 2769 | -5,425,16.5,5,5,16.5 2770 | 4.999985,425,16.5,5,5,16.5 2771 | 15,425,16.5,5,5,16.5 2772 | 25,425,16.5,5,5,16.5 2773 | 115,425,14,5,5,14 2774 | 125,425,14,5,5,14 2775 | 185,425,15.5,5,5,15.5 2776 | 195,425,15.5,5,5,15.5 2777 | 405,425,8,5,5,8 2778 | 415,425,30,5,5,30 2779 | 425,425,8,5,5,8 2780 | 435,425,8,5,5,8 2781 | 445,425,8,5,5,8 2782 | 455,425,8,5,5,8 2783 | 465,425,8,5,5,8 2784 | 475,425,8,5,5,8 2785 | 485,425,8,5,5,8 2786 | 495,425,8,5,5,8 2787 | -215,435,28.5,5,5,28.5 2788 | -205,435,28.5,5,5,28.5 2789 | -195,435,28.5,5,5,28.5 2790 | -175,435,41.5,5,5,41.5 2791 | -165,435,41.5,5,5,41.5 2792 | -155,435,41.5,5,5,41.5 2793 | -145,435,41.5,5,5,41.5 2794 | -125,435,40,5,5,40 2795 | -115,435,40,5,5,40 2796 | -105,435,40,5,5,40 2797 | -95,435,40,5,5,40 2798 | -85,435,40,5,5,40 2799 | -75,435,40,5,5,40 2800 | -25.00002,435,16.5,5,5,16.5 2801 | -15,435,16.5,5,5,16.5 2802 | -5,435,16.5,5,5,16.5 2803 | 5,435,16.5,5,5,16.5 2804 | 15,435,16.5,5,5,16.5 2805 | 25,435,16.5,5,5,16.5 2806 | 35,435,16.5,5,5,16.5 2807 | 175,435,15.5,5,5,15.5 2808 | 185,435,15.5,5,5,15.5 2809 | 195,435,15.5,5,5,15.5 2810 | 395,435,8,5,5,8 2811 | 405,435,8,5,5,8 2812 | 415,435,25,5,5,25 2813 | 425,435,8,5,5,8 2814 | 435,435,8,5,5,8 2815 | 445,435,8,5,5,8 2816 | 455,435,8,5,5,8 2817 | 465,435,8,5,5,8 2818 | 475,435,8,5,5,8 2819 | 485,435,8,5,5,8 2820 | 495,435,8,5,5,8 2821 | -225,445,28.5,5,5,28.5 2822 | -215,445,28.5,5,5,28.5 2823 | -205,445,28.5,5,5,28.5 2824 | -195,445,28.5,5,5,28.5 2825 | -185,445,28.5,5,5,28.5 2826 | -165,445,41.5,5,5,41.5 2827 | -115,445,40,5,5,40 2828 | -105,445,40,5,5,40 2829 | -95,445,40,5,5,40 2830 | -85,445,40,5,5,40 2831 | -35.00001,445,16.5,5,5,16.5 2832 | -25,445,16.5,5,5,16.5 2833 | -15,445,16.5,5,5,16.5 2834 | -5,445,16.5,5,5,16.5 2835 | 4.999985,445,16.5,5,5,16.5 2836 | 15,445,16.5,5,5,16.5 2837 | 24.99998,445,16.5,5,5,16.5 2838 | 35,445,16.5,5,5,16.5 2839 | 45,445,16.5,5,5,16.5 2840 | 165,445,15.5,5,5,15.5 2841 | 175,445,15.5,5,5,15.5 2842 | 185,445,15.5,5,5,15.5 2843 | 215,445,2,5,5,2 2844 | 385,445,8,5,5,8 2845 | 395,445,8,5,5,8 2846 | 405,445,8,5,5,8 2847 | 415,445,8,5,5,8 2848 | 425,445,8,5,5,8 2849 | 435,445,8,5,5,8 2850 | 445,445,8,5,5,8 2851 | 455,445,8,5,5,8 2852 | 465,445,8,5,5,8 2853 | 475,445,8,5,5,8 2854 | 485,445,8,5,5,8 2855 | -235,455,28.5,5,5,28.5 2856 | -225,455,28.5,5,5,28.5 2857 | -215,455,28.5,5,5,28.5 2858 | -205,455,28.5,5,5,28.5 2859 | -195,455,28.5,5,5,28.5 2860 | -185,455,28.5,5,5,28.5 2861 | -175,455,28.5,5,5,28.5 2862 | -155,455,22,5,5,22 2863 | -105,455,40,5,5,40 2864 | -95,455,40,5,5,40 2865 | -45,455,16.5,5,5,16.5 2866 | -35,455,16.5,5,5,16.5 2867 | -25,455,16.5,5,5,16.5 2868 | -15,455,16.5,5,5,16.5 2869 | -5,455,16.5,5,5,16.5 2870 | 5,455,16.5,5,5,16.5 2871 | 15,455,16.5,5,5,16.5 2872 | 25,455,16.5,5,5,16.5 2873 | 34.99999,455,16.5,5,5,16.5 2874 | 45,455,16.5,5,5,16.5 2875 | 55,455,16.5,5,5,16.5 2876 | 155,455,15.5,5,5,15.5 2877 | 165,455,15.5,5,5,15.5 2878 | 175,455,15.5,5,5,15.5 2879 | 185,455,15.5,5,5,15.5 2880 | 205,455,2,5,5,2 2881 | 215,455,2,5,5,2 2882 | 375,455,8,5,5,8 2883 | 385,455,8,5,5,8 2884 | 395,455,8,5,5,8 2885 | 405,455,8,5,5,8 2886 | 415,455,8,5,5,8 2887 | 425,455,8,5,5,8 2888 | 435,455,8,5,5,8 2889 | 445,455,8,5,5,8 2890 | 455,455,8,5,5,8 2891 | 465,455,8,5,5,8 2892 | 475,455,8,5,5,8 2893 | -225,465,28.5,5,5,28.5 2894 | -215,465,28.5,5,5,28.5 2895 | -205,465,28.5,5,5,28.5 2896 | -195,465,28.5,5,5,28.5 2897 | -185,465,28.5,5,5,28.5 2898 | -165,465,22,5,5,22 2899 | -155,465,22,5,5,22 2900 | -145,465,22,5,5,22 2901 | -55,465,16.5,5,5,16.5 2902 | -45.00001,465,16.5,5,5,16.5 2903 | -35,465,16.5,5,5,16.5 2904 | -25,465,16.5,5,5,16.5 2905 | -15,465,16.5,5,5,16.5 2906 | -4.999985,465,16.5,5,5,16.5 2907 | 5,465,16.5,5,5,16.5 2908 | 15.00002,465,16.5,5,5,16.5 2909 | 25,465,16.5,5,5,16.5 2910 | 35,465,16.5,5,5,16.5 2911 | 45.00001,465,16.5,5,5,16.5 2912 | 55,465,16.5,5,5,16.5 2913 | 65.00001,465,16.5,5,5,16.5 2914 | 145,465,15.5,5,5,15.5 2915 | 155,465,15.5,5,5,15.5 2916 | 165,465,15.5,5,5,15.5 2917 | 175,465,15.5,5,5,15.5 2918 | 185,465,15.5,5,5,15.5 2919 | 195,465,15.5,5,5,15.5 2920 | 365,465,8,5,5,8 2921 | 375,465,8,5,5,8 2922 | 385,465,8,5,5,8 2923 | 395,465,8,5,5,8 2924 | 405,465,8,5,5,8 2925 | 415,465,8,5,5,8 2926 | 425,465,8,5,5,8 2927 | 435,465,8,5,5,8 2928 | 445,465,8,5,5,8 2929 | 455,465,8,5,5,8 2930 | --------------------------------------------------------------------------------